Skip to content

Commit

Permalink
Update readme - add topics/services summary
Browse files Browse the repository at this point in the history
  • Loading branch information
sebtiburzio committed Jul 22, 2024
1 parent 43903ab commit d96192c
Show file tree
Hide file tree
Showing 3 changed files with 149 additions and 2 deletions.
6 changes: 5 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,11 @@ Among the output, you should see some messages in green and blue saying 'Loaded.
## Connecting to the Helix ROS system
Connect your device to the Helix RPi, configure network settings and ensure you are able to communicate with the Pi. If you can ping the Pi successfully, you should be able to see the Helix ROS system as well. Probably the easiest way to quickly check if it is working is through Foxglove (see the external interfaces readme).

## Further information
## Reference for Topics and Services

A summary of the relevant topics and services is [here](Topics_and_Services.md). You should still read the userguide information for the relevant systems as well to understand how they work.

## Userguide
See the other documentation in this repo for information about:

0. [Configuration files available to adjust system parameters.](https://github.com/helix-robotics-ag/ros-helix/blob/main/Userguide_0_Configuration.md)
Expand Down
142 changes: 142 additions & 0 deletions Topics_and_Services.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,142 @@
## `/tendon_transmission_node` Namespace

### Source
`ros-helix/helix_transmission/helix_transmission/tendon_transmission.py`

### Topics

`~/commands` `Float64MultiArray[9]`
- Commands the arm tendon position setpoint in [m], relative to the calibrated tendon 0 position, within the configued limits.

`~/current_commands` `Float64MultiArray[9]`
- Commands the arm tendon current in [mA], within the configued limits.

`~/tendon_states` `JointState[9]`
- Position and velocity of arm tendons.

### Services

`~/tendon_transmission_node/set_current` `helix_transmission_interfaces/srv/SetCurrent`

```
float64 current 0.0
---
bool success
string message
```

- Sets all arm tendon current commands to the [mA] value of `current`, within the configued limits.

`~/set_motor_offsets` `std_srvs/Trigger`
- Sets all arm tendon 0 calibration point to the current state, by writing the current motor joint positions to the calibration offsets file.

`~/switch_to_current_control` `std_srvs/Trigger`
- Switches all motor controllers to current mode so that position commands will be ignored.

`~/switch_to_position_control` `std_srvs/Trigger`
- Switches all motor controllers to position mode so that current commands will be ignored.

## `/helix_gripper_node` Namespace

### Source
`ros-helix/helix_gripper/helix_gripper/helix_gripper.py`

### Topics

`~/command_increment` `Float64`
- Moves the gripper tendon by the value in [m], clipped to the configured limit.

## `/helix_cartesian_control_node` Namespace

### Source
`ros-helix-proprietary/helix_cartesian_control/helix_cartesian_control/helix_cartesian_control_node.py`

### Topics

`~/dxdyl_state` `JointState[9]`
- The DxDyL state of the model `[Dx1, Dy1, L1, Dx2, Dy2, L2, Dx3, Dy3, L3]`. Generally updated whenever the model state changes, such as when the model is used to calucalte a Cartesian command, or if the DxDyL state is commanded directly.

`~/cartesian_state` `PoseArray[4]`
- Cartesian poses of the 3 arm section end frames `seg1_end_link`, `seg2_end_link` and `seg3_end_link`, and the gripper TCP frame `helix_tcp`. Calculated from the model FK and updated whenever `~/dxdyl_state` is published.

`~/dxdyl_command` `Float64MultiArray[9]`
- Direct `[Dx1, Dy1, L1, Dx2, Dy2, L2, Dx3, Dy3, L3]` command, which is converted to tendon lengths and commanded as an immediate setpoint.

`~/delta_increment` `TwistStamped`
- Incremental Cartesian command for the gripper TCP, applied in the `frame_id` supplied in the header (which defaults to `origin`). The components of `twist.angular` are applied as rotations around the extrinsic/static axes.

### Services

`~/reset_model` `std_srvs/Trigger`
- Reset the model to the initial/calibration state, and also command tendons to the zero/calibrated lengths.

`~/activate_joystick_control` `std_srvs/Trigger`
- Activate teleoperation control by connecting the `spacenav/twist` topic to `~/delta_increment`.

`~/deactivate_joystick_control` `std_srvs/Trigger`
- Deactivate teleoperation control by disconnecting the `spacenav/twist` topic from `~/delta_increment`.

`~/go_to_gripper_pose_vector` `helix_transmission_interfaces/srv/GoToGripperPoseVector`
- Move the gripper to a goal defined by a gripper TCP point and vector direction.

```
string frame_id
geometry_msgs/Point goal_point
geometry_msgs/Vector3 goal_direction
bool plan_linear
bool ik_uses_prev
---
bool success
string message
```

`~/go_to_gripper_pose_quat` `helix_transmission_interfaces/srv/GoToGripperPoseQuat`
- Move the gripper to a goal defined by a gripper TCP point and quaternion direction.

```
string frame_id
geometry_msgs/Pose goal_pose
bool plan_linear
bool ik_uses_prev
---
bool success
string message
```

`~/go_to_gripper_pose_euler` `helix_transmission_interfaces/srv/GoToGripperPoseEuler`
- Move the gripper to a goal defined by a gripper TCP point and Euler angle set direction.

```
string frame_id
geometry_msgs/Point goal_point
float64[3] goal_euler_angs
string axes "sxyz"
bool plan_linear
bool ik_uses_prev
---
bool success
string message
```

## `ros2_control`

The below topics are used by `ros2_control` to interface directly to the motors. Prefer using the custom topics above, which include transmission, limits etc.

`motor_head_joint_position_controller/commands` `Float64MultiArray[9]`
- Arm tendon motor joint setpoint commands in [rad].

`motor_head_joint_effort_controller/commands` `Float64MultiArray[9]`
- Arm tendon motor current commands in [mA].

`motor_head_joint_state_broadcaster/joint_states` `JointState[9]`
- Arm tendon motor joint position, velocity and current.

`gripper_joint_position_controller/commands` `Float64MultiArray[1]`
- Gripper tendon motor joint setpoint commands in [rad].

`gripper_joint_state_broadcaster/joint_states` `JointState[1]`
- Gripper tendon motor joint position, velocity and current.




3 changes: 2 additions & 1 deletion Userguide_0_Configuration.md
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ joystick_control_speed: 0.05 # Nominal TCP speed [m/s] for joystick. An
```

### `pcc_model.config.yml`
This defines the parameters used to initialise the underlying model for cartesian control. If no file is present, the defaults from the [`HelixKinematicPCCModel`](https://github.com/helix-robotics-ag/helix-models/blob/main/helix_models/helix_kinematic_pcc.py) class will be used.
This defines the parameters used to create the underlying model for cartesian control. If no file is present, the defaults from the [`HelixKinematicPCCModel`](https://github.com/helix-robotics-ag/helix-models/blob/main/helix_models/helix_kinematic_pcc.py) class will be used.

If no file is present, one will **not** be created. If you want to change the parameters, create a file with the below fields. `gripper_length` is probably the parameter you are most likely to want to change, this is the [m] distance in the Z-direction from the arm 'wrist' (`seg3_end_link` frame) to the gripper TCP (`helix_tcp` frame). See the [`helix_models`](https://github.com/helix-robotics-ag/helix-models/tree/main) repo docs for more information on the others.
```
Expand All @@ -55,3 +55,4 @@ k_axial: 1.0
d_limits: [0.7854, 1.571, 1.571]
ws_limits: [[0.055, 0.7854, 0.065, 0.120, 0.7854, 0.085],[0.115, 1.571, 0.150, 0.255, 1.571, 0.150],[0.125, 1.571, 0.165, 0.240, 1.571, 0.185]]
```
Note that all control that relies on the model (incremental and pose-to-pose Cartesian, and direct DxDyL commands) respect the limits defined inside the model.

0 comments on commit d96192c

Please sign in to comment.