Skip to content

Commit

Permalink
Adjustments for position scaler and status, and added script to get a…
Browse files Browse the repository at this point in the history
…ll axis parameter values

Updated for the following features:
- Added Position Scaler consideration in position calculation (higher prio than encoder steps)
- Added Status information in published /tmc_info
- Changed default /tmc_info publish rate to 10Hz (previously 1Hz)
- Added GAP_params.sh to query YAML's axis parameters' values
- Made TMCM-1636 FollowEepromConfig as False and then used calibrated values in YAML
- Updated Maintainer email

Co-Authored-By: Christian Joseph Acar <124771470+CAcarADI@users.noreply.github.com>
  • Loading branch information
mmaralit-adi and CAcarADI committed May 10, 2023
1 parent f9968e7 commit 950c0b0
Show file tree
Hide file tree
Showing 14 changed files with 373 additions and 49 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ project(tmcl_ros)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
geometry_msgs
message_generation
std_msgs
)
Expand Down
22 changes: 22 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -356,6 +356,28 @@ $ ./CAN_interface.sh

> :memo: _Note: If bitrate is changed, it is advised to restart the board and initialize the CAN again using the new bitrate this time._
## Querying the Axis Parameters' Values

The GAP_params.sh (or Get Access Parameters script) collects actual values of the axis parameters listed on the generated yaml. One particular useful case is if the user decided to enable FollowEepromConfig and wanted to know all the parameter values stored in EEPROM. To use this script, it is expected that the tmcl_ros node is running on another terminal. To make the script executable:

```bash
$ cd ~/catkin_ws/src/tmcl_ros/scripts
$ chmod +x GAP_params.sh
```
Then, to execute the script:
```bash
$ ./GAP_params.sh <YAML filename WITHOUT extension> <motor number> <enable description>
```
Where:
- YAML filename is the name of the autogenerated yaml, without the extension, used by the node running from another terminal
- motor number is the number of which motor should the user want to extract the parameters from
- enable description is a boolean argument (represented by Y/N) which can display (or not display) the additional descriptions/range of each parameter in the output

For example, to get the axis parameters' values of TMCM-1636's motor 0 with the description enabled:
```bash
$ ./GAP_params.sh TMCM-1636 0 Y
```

# Limitations
1. No support for multiple/concurrent CAN or TMCL connections yet.
2. No support for interfaces other than CAN yet.
Expand Down
26 changes: 13 additions & 13 deletions config/TMCM-1617_Ext.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -63,35 +63,35 @@ comm_exec_cmd_retries: 1
# Description: tmc_info topics that will contain chosen TMC info that will be published
# Possible values:
# - Any tmc_info topic name
tmc_info_topic: [/tmc_info_0, /tmc_info_1, /tmc_info]
tmc_info_topic: [/tmc_info_0, /tmc_info, /tmc_info]

# cmd_vel topics to subscribe from
# Description: Twist topics that will be the source of target velocity to be set on the TMC
# Possible values:
# - Any Twist topic name
# Note: Only its linear.x will be used (range: -200000 to 200000)
tmc_cmd_vel_topic: [/cmd_vel_0, /cmd_vel_1, /cmd_vel]
tmc_cmd_vel_topic: [/cmd_vel_0, /cmd_vel, /cmd_vel]

# cmd_pos topics to subscribe from
# Description: Int32 topics that will be the source of target position to be set on the TMC
# Possible values:
# - Any Int32 topic name (range: -2147483648 to -2147483647)
tmc_cmd_abspos_topic: [/cmd_abspos_0, /cmd_abspos_1, /cmd_abspos]
tmc_cmd_abspos_topic: [/cmd_abspos_0, /cmd_abspos, /cmd_abspos]

# cmd_pos topics to subscribe from
# Description: Int32 topics that will be the source of target position to be set on the TMC
# Possible values:
# - Any Int32 topic name (range: -2147483648 to -2147483647)
tmc_cmd_relpos_topic: [/cmd_relpos_0, /cmd_relpos_1, /cmd_relpos]
tmc_cmd_relpos_topic: [/cmd_relpos_0, /cmd_relpos, /cmd_relpos]

# cmd_trq topics to subscribe from
# Description: Int32 topics that will be the source of target torque to be set on the TMC
# Possible values:
# - Any Int32 topic name (range: -60000 to 60000 mA)
tmc_cmd_trq_topic: [/cmd_trq_0, /cmd_trq_1, /cmd_trq]
tmc_cmd_trq_topic: [/cmd_trq_0, /cmd_trq, /cmd_trq]

# Wheel diameter attached to the motor (in meters)
# Description: Wheel diameter that is attached on the motor shaft directly. This is to convert linear values to rpm
# Description: Wheel diameter that is attached on the motor. This is to convert linear values to rpm
# Note: If wheel diameter is 0, cmd_vel is equal to rpm
wheel_diameter: 0.25

Expand All @@ -100,27 +100,27 @@ wheel_diameter: 0.25
# Possible values:
# - 0: Not used
# - 1: Active
en_motors: [1, 1, 0]
en_motors: [1, 0, 0]

# Publish TMC information
# Decription: Enables/disables publishing of TMC information
# Possible values:
# - true: Enabled
# - false: Disabled
en_pub_tmc_info: [true, true, false]
en_pub_tmc_info: [true, false, false]

# Publish rate of TMC information
# Decription: Publish rate (hertz) of TMC information
# Possible values: 0 - 50
pub_rate_tmc_info: 1
# Possible values: 10 - 100
pub_rate_tmc_info: 10

########## TMC Information

# Enable/Disable axis parameters that the user can optionally publish every publish rate as long as en_pub_tmc_info is true

pub_actual_vel: [true, true, false]
pub_actual_trq: [true, true, false]
pub_actual_pos: [true, true, false]
pub_actual_vel: [true, false, false]
pub_actual_trq: [true, false, false]
pub_actual_pos: [true, false, false]

##########################################################
##########################################################
Expand Down
40 changes: 20 additions & 20 deletions config/TMCM-1636_Ext.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -63,35 +63,35 @@ comm_exec_cmd_retries: 1
# Description: tmc_info topics that will contain chosen TMC info that will be published
# Possible values:
# - Any tmc_info topic name
tmc_info_topic: [/tmc_info_0, /tmc_info_1, /tmc_info]
tmc_info_topic: [/tmc_info_0, /tmc_info, /tmc_info]

# cmd_vel topics to subscribe from
# Description: Twist topics that will be the source of target velocity to be set on the TMC
# Possible values:
# - Any Twist topic name
# Note: Only its linear.x will be used (range: -200000 to 200000)
tmc_cmd_vel_topic: [/cmd_vel_0, /cmd_vel_1, /cmd_vel]
tmc_cmd_vel_topic: [/cmd_vel_0, /cmd_vel, /cmd_vel]

# cmd_pos topics to subscribe from
# Description: Int32 topics that will be the source of target position to be set on the TMC
# Possible values:
# - Any Int32 topic name (range: -2147483648 to -2147483647)
tmc_cmd_abspos_topic: [/cmd_abspos_0, /cmd_abspos_1, /cmd_abspos]
tmc_cmd_abspos_topic: [/cmd_abspos_0, /cmd_abspos, /cmd_abspos]

# cmd_pos topics to subscribe from
# Description: Int32 topics that will be the source of target position to be set on the TMC
# Possible values:
# - Any Int32 topic name (range: -2147483648 to -2147483647)
tmc_cmd_relpos_topic: [/cmd_relpos_0, /cmd_relpos_1, /cmd_relpos]
tmc_cmd_relpos_topic: [/cmd_relpos_0, /cmd_relpos, /cmd_relpos]

# cmd_trq topics to subscribe from
# Description: Int32 topics that will be the source of target torque to be set on the TMC
# Possible values:
# - Any Int32 topic name (range: -60000 to 60000 mA)
tmc_cmd_trq_topic: [/cmd_trq_0, /cmd_trq_1, /cmd_trq]
tmc_cmd_trq_topic: [/cmd_trq_0, /cmd_trq, /cmd_trq]

# Wheel diameter attached to the motor (in meters)
# Description: Wheel diameter that is attached on the motor shaft directly. This is to convert linear values to rpm
# Description: Wheel diameter that is attached on the motor. This is to convert linear values to rpm
# Note: If wheel diameter is 0, cmd_vel is equal to rpm
wheel_diameter: 0.25

Expand All @@ -100,27 +100,27 @@ wheel_diameter: 0.25
# Possible values:
# - 0: Not used
# - 1: Active
en_motors: [1, 1, 0]
en_motors: [1, 0, 0]

# Publish TMC information
# Decription: Enables/disables publishing of TMC information
# Possible values:
# - true: Enabled
# - false: Disabled
en_pub_tmc_info: [true, true, false]
en_pub_tmc_info: [true, false, false]

# Publish rate of TMC information
# Decription: Publish rate (hertz) of TMC information
# Possible values: 0 - 50
pub_rate_tmc_info: 1
# Possible values: 10 - 100
pub_rate_tmc_info: 10

########## TMC Information

# Enable/Disable axis parameters that the user can optionally publish every publish rate as long as en_pub_tmc_info is true

pub_actual_vel: [true, true, false]
pub_actual_trq: [true, true, false]
pub_actual_pos: [true, true, false]
pub_actual_vel: [true, false, false]
pub_actual_trq: [true, false, false]
pub_actual_pos: [true, false, false]

##########################################################
##########################################################
Expand All @@ -137,7 +137,7 @@ pub_actual_pos: [true, true, false]
# Possible values:
# - true: Follow all the motor configuration as-is (EEPROM values set as part of TMC firmware or as set in TMCL-IDE)
# - false: Have user set all motor configurations in this YAML (below)
FollowEepromConfig: true
FollowEepromConfig: false

########## Sensor Selection Settings

Expand Down Expand Up @@ -197,11 +197,11 @@ HallSensorOffset_Ext: [0, 0, 0]

# Encoder direction
# Description: Encoder direction in a way that ROR increases position counter
EncoderDirection_Ext: [1, 0, 0]
EncoderDirection_Ext: [0, 0, 0]

# Encoder steps
# Description: Encoder steps per full motor rotation
EncoderSteps_Ext: [4096, 0, 0]
EncoderSteps_Ext: [16384, 0, 0]

# Encoder init mode
# Description: Encoder init mode
Expand All @@ -211,23 +211,23 @@ EncoderInitMode_Ext: [0, 0, 0]

# Torque P
# Description: P parameter for current PID regulator
TorqueP_Ext: [300, 0, 0]
TorqueP_Ext: [1500, 0, 0]

# Torque I
# Description: I parameter for current PID regulator
TorqueI_Ext: [500, 0, 0]

# Velocity P
# Description: P parameter for velocity PID regulator
VelocityP_Ext: [400, 0, 0]
VelocityP_Ext: [131, 0, 0]

# Velocity I
# Description: I parameter for velocity PID regulator
VelocityI_Ext: [100, 0, 0]
VelocityI_Ext: [49, 0, 0]

# Position P
# Description: P parameter for position PID regulator
PositionP_Ext: [10, 0, 0]
PositionP_Ext: [11, 0, 0]

########## Brake Chopper Settings

Expand Down
6 changes: 6 additions & 0 deletions config/autogenerated/TMCM-1617.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,12 @@

TotalMotors: 1

# Descriptions for possible values of StatusFlags:
# Size:: 32 [bit]
StatusFlags: [1, 156, 0, 0, 0]
StatusFlagsRegName: [OVERCURRENT, UNDERVOLTAGE, OVERVOLTAGE, OVERTEMPERATURE, MOTORHALTED, HALLERROR, DRIVER_ERROR, INIT_ERROR, STOP_MODE, VELOCITY_MODE, POSITION_MODE, TORQUE_MODE, POSITION_END, MODULE_INITIALIZED]
StatusFlagsRegShift: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 14, 15]

# Descriptions for possible values of SupplyVoltage:
# Range:: 0 to 1000 [0.1V]
SupplyVoltage: [1, 220, 240, 0, 1000]
Expand Down
6 changes: 6 additions & 0 deletions config/autogenerated/TMCM-1636.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,12 @@

TotalMotors: 1

# Descriptions for possible values of StatusFlags:
# Size:: 32 [bit]
StatusFlags: [1, 156, 0, 0, 0]
StatusFlagsRegName: [OVERCURRENT, UNDERVOLTAGE, OVERVOLTAGE, OVERTEMPERATURE, MOTORHALTED, HALLERROR, DRIVER_ERROR, INIT_ERROR, STOP_MODE, VELOCITY_MODE, POSITION_MODE, TORQUE_MODE, POSITION_END, MODULE_INITIALIZED, IIT_EXCEEDED_1, IIT_EXCEEDED_2]
StatusFlagsRegShift: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 14, 15, 16, 17]

# Descriptions for possible values of SupplyVoltage:
# Range:: 0 to 1000 [100mV]
SupplyVoltage: [1, 220, 480, 0, 1000]
Expand Down
4 changes: 3 additions & 1 deletion include/tmcl_ros/tmcl_interpreter.h
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,8 @@ typedef enum
/* LUT row indeces of get-able/set-able Axis Parameters */
typedef enum
{
ROW_IDX_SupplyVoltage = 0,
ROW_IDX_StatusFlags = 0,
ROW_IDX_SupplyVoltage,
ROW_IDX_TargetVelocity,
ROW_IDX_ActualVelocity,
ROW_IDX_TargetPosition,
Expand Down Expand Up @@ -175,6 +176,7 @@ typedef enum

/* LUT row strings of get-able/set-able Axis Parameters */
std::vector<std::string> tmcl_lut_row_str = {
"StatusFlags",
"SupplyVoltage",
"TargetVelocity",
"ActualVelocity",
Expand Down
6 changes: 5 additions & 1 deletion include/tmcl_ros/tmcl_ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
#define TIMEOUT_MS_DEFAULT 10
#define EXEC_CMD_RETRIES_MAX 3
#define EXEC_CMD_RETRIES_DEFAULT 1
#define PUB_RATE_MAX 50
#define PUB_RATE_MAX 100
#define RATE_20KBPS 20000
#define RATE_50KBPS 50000
#define RATE_100KBPS 100000
Expand Down Expand Up @@ -97,6 +97,10 @@ class TmclROS
std::vector<std::vector<int>> ap_cfg;
std::vector<std::vector<int>> ap_cfg_ext;

/* Separate vectors for registers of Statusflags */
std::vector<std::string> param_status_flags_reg_name;
std::vector<int> param_status_flags_reg_shift;

/* Handle for TmclInterpreter */
TmclInterpreter *tmcl;

Expand Down
2 changes: 2 additions & 0 deletions msg/TmcInfo.msg
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
std_msgs/Header header
string interface_name
float32 board_voltage
int32 status_flag
string status
uint8 motor_num
float32 velocity
int32 position
Expand Down
4 changes: 3 additions & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,15 +4,17 @@
<version>1.0.0</version>
<description>The tmcl_ros package</description>

<maintainer email="guest@todo.todo">guest</maintainer>
<maintainer email="ROS@analog.com">ROS@analog.com</maintainer>

<license>MIT</license>

<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>message_generation</build_depend>
<build_export_depend>roscpp</build_export_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>message_runtime</exec_depend>
<depend>std_msgs</depend>

Expand Down
Loading

0 comments on commit 950c0b0

Please sign in to comment.