Issues with initializing motor driver using canopen_motor_node

asked 2021-08-24 02:22:10 -0500

JohnTGZ gravatar image

Hi everyone! Im facing issues with initializing the Technosoft iPOS8010 BX-CAN motor driver using the canopen_motor_node. I have tried it using the 2 configurations described below.

In the 1st set-up, I tried using the bare minimum in canopen_motor_node configs (Code Block [A], [B1], [C], [D]). From the terminal output [E1] and candump output [F1], it seems like I am stuck at initializing the motors and it does not progress beyond this stage.

In the 2nd set-up, I added RPDO remapping to the configs (Code Block [A], [B2], [C], [D]). From the candump output [F2], it seems that I have done the remapping properly. Yet, from the terminal output [E2], the canopen_motor_node seems to have runtime errors.

I have a few questions about getting the motor driver to initialize:

  1. Could this issue be in part due to the improper configuration of the controller_spawners?
  2. What are some issues with the way I might have configured my RPDO remapping parameters?
  3. Do I need TPDO remapping as well in order for this to work?

1st Set-up: Bare Minimum

[A]: Launch file (canopen_motor.launch)

<launch>
  <!-- Upload URDF -->
  <param name="robot_description" 
        command="$(find xacro)/xacro '$(find canopen_controller)/urdf/motor1.urdf.xacro'" />
  <!-- Publish TF transforms -->
  <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
      <param name="publish_frequency" value="50.0" />
      <param name="tf_prefix" value="" />
  </node>

  <!-- Start canopen motor node -->
  <node name="driver" pkg="canopen_motor_node" type="canopen_motor_node" output="screen" clear_params="true" launch-prefix="">
    <rosparam command="load" file="$(find canopen_controller)/config/canopen_motor.yaml" />
    <remap from="joint_states" to="/joint_states"/>
  </node>

  <!-- Spawn Controllers -->
  <rosparam command="load" 
            ns="motor1_joint_state_controller" 
            file="$(find canopen_controller)/config/joint_state_controller.yaml" />
  <rosparam command="load" 
            ns="velocity_controller" 
            file="$(find canopen_controller)/config/velocity_controller.yaml" />

  <node name="controller_spawner" pkg="controller_manager" type="spawner" 
        args="motor1_joint_state_controller
              velocity_controller" />

</launch>

[B1]: Canopen motor config (canopen_motor.yaml)

bus:
  device: can0 # socketcan network
  loopback: true # socket should loop back messages
  driver_plugin: can::SocketCANInterface
  master_allocator: canopen::SimpleMaster::Allocator

sync:
  interval_ms: 10 # set to 0 to disable sync
  overflow: 0 # overflow sync counter at value or do not set it (0, default)

update_ms: 100 #update interval of control loop, must be set explicitly if sync is disabled

defaults: # optional, all defaults can be overwritten per node
  motor_allocator: canopen::Motor402::Allocator
  pos_to_device: "rint(rad2deg(pos)/0.18)"
  pos_from_device: "deg2rad(obj6064)*0.18"
  vel_to_device: "rint(rad2deg(vel)/0.18)"
  vel_from_device: "deg2rad(obj606C)*0.18"
  eff_to_device: "rint(eff)"
  eff_from_device: "0"

nodes:
  - name: motor1_joint
    id: 1
    eds_pkg: canopen_controller # optionals package  name for relative path
    eds_file: "config/iPOS_D_v1_04.eds" # path to EDS/DCF file

[C]: Joint state publisher(joint_state_controller.yaml)

# Publish all joint states 
type: "joint_state_controller/JointStateController"
publish_rate: 50

[D]: Joint state controller (velocity_controller.yaml)

# Velocity Controllers
type: "velocity_controllers/JointVelocityController"
joint: motor1_joint
#Profiled Velocity is ID == 3
required_drive_mode: 3

[E1]: Resulting Output from Terminal

...
process[robot_state_publisher-2]: started with pid [18192]
process[driver-3]: started with pid [18193]
process[controller_spawner-4]: started with pid [18194]
[ INFO] [1629778446.579162807]: Using fixed control period: 0.010000000
[ INFO] [1629778448.637259880]: Initializing...
[ INFO ...
(more)
edit retag flag offensive close merge delete