ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

command igus-dryve with canopen_motor_node

asked 2019-07-17 08:56:49 -0500

mtROS gravatar image

updated 2019-07-23 09:31:49 -0500

Hy there,

i am trying to implement a controller for a igus-dryve motor drive on ros-kinetic. I am using canopen and the ros_canopen package to communicate over a sysWORXX USBCanmodule 1 with the igus-dryve and have everything setup properly (stepper motor in closed loop beeing controllable over the igus webinterface and set to accept CANopen communication which is wired correctly).

Calling rosservice call /joint/driver/init works fine, axis gets reset, return is True and the ros-controllers are loading.

Here comes my issue:

  1. How do I actually move/command the motor? By setting the actual values of the Object by rosservice call /joint/driver/setObject ? Or does the canopen_motor_node take care of all the communication in order to drive the motor? In that case how do I forward a positioning command? I tried to call rostopic pub /lifter_ros/lifter_joint_position_controller/command std_msgs/Float64 "data: 1.0" but no reactions.
  2. Additionally i was thinking about if ros_control is really needed in my use-case? igus-dryve already performs a closed-loop control so isn`t ros_control a layer ontop and too much?

Please find attached my controller config:

joint_state_controller:
  type: joint_state_controller/JointStateController
  publish_rate: 50
lifter_joint_position_controller:
  type: position_controllers/JointPositionController
  joint: lifter_joint
  required_drive_mode: 1

And my node layer:

name: igus-dryve 

defaults:
  eds_pkg: lifter_ros
  eds_file: "config/igus_dryve_D1.eds" #electrical desciption file of igus dryve

  #the following scaling is due to 16bit value range limitation of velocity command in vl mode (2)
  #vel_to_device: "rint(rad2deg(vel)*250)"
  #dcf_overlay: # "ObjectID": "ParameterValue" (both as strings)
  #  "604Csub1": "1" # vl dimension factor numerator
  #  "604Csub2": "24000" # vl dimension factor denominator
#defaults: # optional, all defaults can be overwritten per node
  # canopen_chain_node settings ..
  motor_allocator: canopen::Motor402::Allocator # select allocator for motor layer
#motor_layer: #settings passed to motor layer (plugin-specific)
  switching_state: 5 # (Operation_Enable), state for mode switching
  pos_to_device: "rint(rad2deg(pos)*1000)" # rad -> mdeg
  pos_from_device: "deg2rad(obj6064)/1000" # actual position [mdeg] -> rad
  vel_to_device: "rint(rad2deg(vel)*1000)" # rad/s -> mdeg/s
  vel_from_device: "deg2rad(obj606C)/1000" # actual velocity [mdeg/s] -> rad/s
  eff_to_device: "rint(eff)" # just round to integer
  eff_from_device: "0" # unset
nodes:
  lifter_joint:
    id: 2

and my launchfile:

?xml version="1.0"?>
<launch>
  <!-- send urdf to param server -->
  <param name="robot_description" command="cat '$(find lifter_ros)/urdf/lifter.urdf'" />
  <!-- robot state publisher -->
  <node ns="lifter_ros" pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
      <param name="publish_frequency" type="double" value="50.0" />
      <param name="tf_prefix" type="string" value="" />
      <!--remap from="joint_states" to="/arm/joint_states"/-->
  </node>

  <node ns="lifter_ros" name="driver" pkg="canopen_motor_node" type="canopen_motor_node" output="screen" clear_params="true" launch-prefix="">
     <rosparam command="load" file="$(find lifter_ros)/config/CANopen_layer.yaml" />
     <rosparam command="load" file="$(find lifter_ros)/config/node_layer.yaml" />
  </node>
  <!-- controllers -->
  <rosparam ns="lifter_ros" command="load" file="$(find lifter_ros)/config/dryve_controller.yaml" />
 <!-- start_controllers -->
  <node ns="lifter_ros" name="lifter_ros_controller_spawner" pkg="controller_manager" type="controller_manager" args="spawn joint_state_controller" respawn="false" output="screen"/>
</launch>

I would highly appreciate your help!

Thanks

EDIT Regarding the controllers: The output says the controller ... (more)

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
0

answered 2019-07-19 09:08:01 -0500

Mathias Lüdtke gravatar image

updated 2019-07-19 09:08:32 -0500

How do I actually move/command the motor?

You have to publish to the command topic of the lifter_joint_position_controller (just like in your example). If it does not work, please double-check that the controller was actually started. It looks like you have copied the parameters from the Schunk LWA4 packages, perhaps IGUS needs different settings.

Additionally i was thinking about if ros_control is really needed in my use-case?

ros_control provides a generic controller interface, so all users can choose their controllers.

igus-dryve already performs a closed-loop control so isn`t ros_control a layer ontop and too much?

position_controllers/JointPositionController just forwards the command, i.e., it connects CANopen and ROS.

edit flag offensive delete link more

Comments

Thank you for your answer!

It looks like you have copied the parameters from the Schunk LWA4 packages, perhaps IGUS needs different settings.

Do you mean the settings of the canopen_motor_node? I am a bit confused of what i would have to actually change...?

I had a look at different examples that use a dcf overlay but have not idea where to start.

Please see Edit for controller up check.

mtROS gravatar image mtROS  ( 2019-07-23 04:19:42 -0500 )edit

I was referring to https://github.com/ipa320/schunk_robo.... According to your config, if you command "1.0" [rad], the device will receive the target 57296 [millidegrees]. You should be able to find this in the candump as well.

As a starting point you should first check your unit settings and verify it by reading the joint states in different positions.

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2019-07-23 08:47:12 -0500 )edit

I can't find any message in the candump beeing send when calling /command...

When i rostopic echo /joint_states I just recieve zeros and i can't actually move the motor by hand. header: seq: 38525 stamp: secs: 1563890889 nsecs: 267513294 frame_id: '' name: ['lifter_joint'] position: [0.0] velocity: [0.0] effort: [0.0]

Could you please check my edit above? Seems that the controllers are working properly, arn't they?

mtROS gravatar image mtROS  ( 2019-07-23 09:08:28 -0500 )edit

The controllers seem to work, but they just forward message, so it is hard to make them fail.

It looks like your unit settings are wrong: your device is a linear actuator, but your config is for rotary devices. Better check the manual.

You can move the drive to a known location (with the IGUS tool) and check the the position afterwards.

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2019-07-23 09:22:29 -0500 )edit

Thank you for your support!

  1. Changed the unit settings to rotary.

  2. I moved the motor with the igus-tool and was then calling via /get_object the object 6064 "Position actual value"---> the rostopic echo of the joint states then updates the value.

mtROS gravatar image mtROS  ( 2019-07-23 09:41:09 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2019-07-17 08:56:49 -0500

Seen: 615 times

Last updated: Jul 23 '19