You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Hi all, I'm going to use ros2 to drive a Kollmorgen RGM joint module, but I can't drive the motor, it's been bugging me for almost a month now! My main goal is to implement closed-loop servo control of motor speed in csv mode, When I start the ros2_control node, the motors can go into the OP state, but the joint motors are not enabled at this point, because if the joint motors are enabled, the holding brake on the joint motors will release and make a popping sound. So I went through a node and sent control words to the controller of ros2_control which are decimal 6,7 and 15 respectively but the state of the motor didn't change, why is that?
I made the following file configuration:
Here is the slave.yaml file:
vendor_id: 0x0000006a
product_id: 0x00002020
# assign_activate: 0x0330 # DC Synch register
auto_fault_reset: false # true = automatic fault reset, false = fault reset on rising edge command interface "reset_fault"
sdo: # sdo data to be transferred at drive startup
# - {index: 0x60C2, sub_index: 1, type: int8, value: 10} # Set interpolation time for cyclic modes to 10 ms
# - {index: 0x60C2, sub_index: 2, type: int8, value: -3} # Set base 10-3s
rpdo: # RxPDO = receive PDO Mapping
- index: 0x1700
channels:
- {index: 0x6040, sub_index: 0, type: uint16, command_interface: control_word, default: .nan} # Control word
- {index: 0x607a, sub_index: 0, type: int32, default: 0.0} # Target position
- {index: 0x60ff, sub_index: 0, type: int32, command_interface: target_velocity, default: .nan} # Target velocity
- {index: 0x6071, sub_index: 0, type: int16, default: 0} # Target torque
- {index: 0x60b0, sub_index: 0, type: int32, default: 0} # Offset position
- {index: 0x60b1, sub_index: 0, type: int32, default: 0} # Offset velocity
- {index: 0x60b2, sub_index: 0, type: int16, default: 0} # Offset torque
- {index: 0x6060, sub_index: 0, type: int8, default: 9} # Mode of operation
- {index: 0x2078, sub_index: 1, type: uint16, default: 0} # Digital Output Functionalities
- {index: 0x60b8, sub_index: 0, type: uint16, default: 0} # Touch Probe Function
tpdo: # TxPDO = transmit PDO Mapping
- index: 0x1b00
channels:
- {index: 0x6041, sub_index: 0, type: uint16, state_interface: state_word} # Status word
- {index: 0x6064, sub_index: 0, type: int32, state_interface: position} # Position actual value
- {index: 0x606c, sub_index: 0, type: int32, state_interface: velocity} # Velocity actual value
- {index: 0x60f4, sub_index: 0, type: int32} # Position loop error
- {index: 0x6077, sub_index: 0, type: int16} # Torque actual value
- {index: 0x60C2, sub_index: 1, type: int8, value: 10} # Set interpolation time for cyclic modes to 10 ms
- {index: 0x60C2, sub_index: 2, type: int8, value: -3} # Set base 10-3s
- {index: 0x6061, sub_index: 0, type: int8} # Mode of operation display
- {index: 0x2071, sub_index: 1, type: int16} # Digital Input Functionalities State
- {index: 0x60b9, sub_index: 0, type: int16} # Touch Probe Status
- {index: 0x60ba, sub_index: 0, type: int32} # Touch Probe Position 1 Positive Value
- {index: 0x60bb, sub_index: 0, type: int32} # Touch Probe Position 1 Negative Value
sm:
- {index: 0, type: output, pdo: ~, watchdog: disable}
- {index: 1, type: input, pdo: ~, watchdog: disable}
- {index: 2, type: output, pdo: rpdo, watchdog: enable}
- {index: 3, type: input, pdo: tpdo, watchdog: enable}
Hi,
The line
[ros2_control_node-1] STATE: Not Ready to Switch On with status word: 0
said that your drive is not well configured.
Did you test your drive alone with the software provided with your drive ?
You have to find the root cause of this problem first.
Hi all, I'm going to use ros2 to drive a Kollmorgen RGM joint module, but I can't drive the motor, it's been bugging me for almost a month now! My main goal is to implement closed-loop servo control of motor speed in csv mode, When I start the ros2_control node, the motors can go into the OP state, but the joint motors are not enabled at this point, because if the joint motors are enabled, the holding brake on the joint motors will release and make a popping sound. So I went through a node and sent control words to the controller of ros2_control which are decimal 6,7 and 15 respectively but the state of the motor didn't change, why is that?
I made the following file configuration:
Here is the slave.yaml file:
here is the xacro:
here is controller_manage.yaml:
All the types are defined as uint16_t, can i change it?
The text was updated successfully, but these errors were encountered: