Note: This tutorial was tested with ROS Melodic and assumes that you have some basic knowledge of ROS and CANopen. Take care of the wiring and safety instructions mentioned by the "Hardware Reference" of your EPOS4 controller!. |
Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Using maxon EPOS4 in Profile Operating Modes
Description: This tutorial explains how to use Profile Modes of maxon EPOS4 controller such as Profile Position Mode and Profile Velocity Mode with ros_canopen for a single motor.Keywords: canopen, ros_canopen, epos4, maxon, profile position, profile velocity
Tutorial Level: INTERMEDIATE
Next Tutorial: Using maxon EPOS4 in Cyclic Synchronous Operating Modes
Contents
Please adapt the code to the needs of your concrete application. Any warranty for proper functionality is excluded and has to be ensured based on tests within the concrete system environment. Take care of the wiring and safety instructions mentioned by the "Hardware Reference" of the corresponding controller!
This tutorial explains how to use maxon EPOS4 controller with ros_canopen. It should work with any combination of EPOS4 version and motor, as long as the motor dependent parameters are set properly. For simplification, only a single EPOS4 controller will be used. However the following configuration files can be easily extended to multi-axis robotic systems.
For more information and specific use cases using NVIDIA Jetson TX2 and Raspberry Pi, along with troubleshooting tips please visit this github repository.
EPOS4 setup
Hardware setup
For wiring, please refer to the official maxon EPOS4 Hardware Reference manual corresponding to your controller. You will find it in the Download section after selecting your controller. It is recommended to keep the automatic bit rate detection on the DIP switch SW1 (factory default). Don’t forget to set the bus termination (7th switch to ON) on your last node.
Software setup with EPOS Studio
To get EPOS Studio software use the “Download EPOS Setup” button at the bottom of maxon EPOS website. It is recommended to update your EPOS4 with the latest firmware. After setting up your EPOS4 with the Startup Wizard please proceed to the regulation tuning.
Finally the CANopen Wizard will help you setting up the PDO mapping that is expected by ros_canopen. On the Receive PDOs window, verify the COB-IDs, check "valid" and set Transmission to "synchronous" for all 4 PDOs. Finally set the following mapping:
RxPDO 1
- Controlword
- Target velocity
RxPDO 2
- Target position
- Profile velocity
RxPDO 3
- Profile acceleration
- Profile deceleration
RxPDO 4
- Target torque
- Modes of operation
On the Transmit PDOs window, verify the COB-IDs, check both "valid" and "RTR" and set Transmission to "synchronous" for all 4 PDOs. Finally you can set the following mapping:
TxPDO 1
- Statusword
- Modes of operation display
TxPDO 2
- Velocity demand value
- Velocity actual value
TxPDO 3
- Position actual value
- Velocity actual value averaged
TxPDO 4 (empty)
In the Error Protocol tab, you can leave the Heartbeat consumer and producer unchecked.
You will need to export a DCF file. For that just right click on your EPOS4 controller, go to Wizards -> Parameter Import/Export, type a file name and do “Export Parameters to File”.
The next steps assume that there is a SocketCAN interface present on the linux system where ROS is installed. For more information you can follow the steps explained here.
ROS package setup
You can get a package example from this Github repository or create your own using the following steps.
Package structure
You can create a new ROS package in your workspace with the following dependencies:
$ catkin_create_pkg epos4_canopen std_msgs std_srvs rospy roscpp roslib
Create the following directories in your new package:
config
launch
urdf
Configuration files
For ros_canopen to function properly, you need to define some parameters in YAML files.
CANopen Bus parameters
In the config folder you can create a configuration file called can.yaml and copy/paste the following content:
bus: device: can0 # SocketCAN network interface # loopback: false # Make the SocketCAN loop back messages # driver_plugin: can::SocketCANInterface master_allocator: canopen::SimpleMaster::Allocator sync: interval_ms: 10 # 10 ms is recommended for non real-time systems, set to 0 to disable sync # update_ms: <interval_ms> # Update interval of control loop, must be set explicitly if sync is disabled overflow: 0 # overflow sync counter at value or do not set it (0, default) heartbeat: # simple heartbeat producer, optional! rate: 20 # heartbeat rate msg: "77f#05" # message to send, cansend format: heartbeat of node 127 with status 5=Started
This file allows you to specify which Linux CAN interface to use, for example can0. It also allows you to set a SYNC message (more details of its usage will be seen in the next tutorial covering Cyclic Synchronous Modes) and Heartbeat.
Controller parameters
Depending on if you are using Profile Position Mode or Profile Velocity Mode, chose the correct file to use. You can of course mix the two types of controllers in the same YAML file later on.
Create a configuration file called controller.yaml and copy/paste the chosen content among the two types of Profile Modes:
- Profile Position Mode
joint_names: [base_link1_joint] joint_state_controller: type: joint_state_controller/JointStateController publish_rate: 50 joint_group_position_controller: type: position_controllers/JointGroupPositionController joints: - base_link1_joint required_drive_mode: 1 base_link1_joint_position_controller: type: position_controllers/JointPositionController joint: base_link1_joint required_drive_mode: 1
For Profile Position Mode set the required_drive_mode to 1 as explained in canopen_402 wiki page.
- Profile Velocity Mode
joint_names: [base_link1_joint] joint_state_controller: type: joint_state_controller/JointStateController publish_rate: 50 ## velocity controller joint_group_velocity_controller: type: velocity_controllers/JointGroupVelocityController joints: - base_link1_joint required_drive_mode: 3 base_link1_joint_velocity_controller: type: velocity_controllers/JointVelocityController joint: base_link1_joint required_drive_mode: 3
For Profile Velocity Mode set the required_drive_mode to 3 as explained in canopen_402 wiki page.
Be careful that the joint name should correspond to the one defined in the URDF and launch file explained later in this tutorial.
Node parameters
Create a configuration file called node.yaml and copy/paste the following content:
nodes: node1: id: 1 name: base_link1_joint eds_pkg: epos4_ros_canopen # optionals package name for relative path eds_file: "config/epos4_node1.dcf" # path to EDS/DCF file defaults: # optional, all defaults can be overwritten per node # eds_pkg: my_config_package # optional package name for relative path # eds_file: "my_config.dcf" # path to EDS/DCF file # dcf_overlay: # "ObjectID": "ParameterValue" (both as strings) # "6098": "0" # No homing operation required # "1016sub1" : "0x7F0064" # heartbeat timeout of 100 ms for master at 127 # "1017": "100" # heartbeat producer # 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: 2 # (Operation_Enable), state for mode switching. Drive mode of operation from canopen_402 wiki pos_to_device: "pos" # inc pos_from_device: "obj6064" # inc vel_to_device: "vel" # rpm vel_from_device: "obj606C" # rpm eff_to_device: "rint(eff)" # just round to integer eff_from_device: "0" # unset
Make sure to replace eds_pkg and eds_file with your package and file name.
In case you are using Homing Mode, you can use the dcf_overlay to set some parameters. For example, if you are using the Homing method -3 (Current Threshold Positive Speed), then you could set the following parameters (please adapt the values to your motor):
defaults: # optional, all defaults can be overwritten per node dcf_overlay: # "ObjectID": "ParameterValue" (both as strings) # Homing mode settings "6065": "2000" # Following error window "30B1": "1000" # Home offset move distance "607F": "1300" # Max profile velocity "6085": "10000" # Quick stop deceleration "6099sub1": "100" # Speed for switch search "6099sub2": "10" # Speed for zero search "609A": "1000" # Homing acceleration "30B2": "1500" # Current threshold for homing mode
Finally, for simplicity they are no unit conversions applied, so that it will be possible to send and read "inc" positions and "rpm" velocities. We will see how to write unit conversions taking care of the gearbox ratio and encoder resolution in the next tutorial.
ROS parameters
Optionally you can create a file called ros.yaml and copy/paste the following content:
defaults: # optional, all defaults can be overwritten per node publish: ["1A00"] # list of objects to be published (one topic per node) nodes: node1: # ... #publish: ["1003sub0!"] # list of objects to be published (one topic per node) node2: # ...
DCF file
Finally, place your DFC file exported previously in that config folder.
The current official version of ros_canopen can’t parse boolean DataType (0x1) objects. It is therefore necessary to delete the only boolean DataType object, [2200sub2] (Internal valid logic supply), then change the SubNumber of [2200] to 2 and ParameterValue of [2200sub0] to 1:
Your original DCF section for object [2200] must look like this:
[2200] SubNumber=3 ParameterName=Power supply ObjectType=0x9 [2200sub0] ParameterName=Highest sub-index supported ObjectType=0x7 DataType=0x5 AccessType=ro DefaultValue=2 PDOMapping=0 ObjFlags=1 ParameterValue=2 [2200sub1] ParameterName=Power supply voltage ObjectType=0x7 DataType=0x6 AccessType=ro PDOMapping=0 ObjFlags=3 [2200sub2] ParameterName=Internal valid logic supply ObjectType=0x7 DataType=0x1 AccessType=ro PDOMapping=0 ObjFlags=1
And you need to change it to this:
[2200] SubNumber=2 ParameterName=Power supply ObjectType=0x9 [2200sub0] ParameterName=Highest sub-index supported ObjectType=0x7 DataType=0x5 AccessType=ro DefaultValue=2 PDOMapping=0 ObjFlags=1 ParameterValue=1 [2200sub1] ParameterName=Power supply voltage ObjectType=0x7 DataType=0x6 AccessType=ro PDOMapping=0 ObjFlags=3
The last thing to modify is the Homing method DefaultValue in case you are not using a Homing Mode. In that case, change the default and parameter values from 7 to 0:
[6098] ParameterName=Homing method ObjectType=0x7 DataType=0x2 AccessType=rww DefaultValue=0 PDOMapping=0 ObjFlags=0 ParameterValue=0
The Homing method value 0 means “no Homing method required” according to CiA 402 standard.
URDF/XACRO file
In the urdf folder you can create a configuration file called maxon_epos4.xacro and copy/paste the following content:
1 <?xml version="1.0"?>
2 <!-- maxon EPOS4 example with 1 DOF -->
3 <robot name="maxon_epos4" xmlns:xacro="http://www.ros.org/wiki/xacro">
4
5 <!-- Base Link -->
6 <link name="base_link">
7 </link>
8
9 <!-- Link1 Link -->
10 <link name="link1_link">
11 </link>
12
13 <!-- Joint between Base Link and Link1 Link -->
14 <joint name="base_link1_joint" type="revolute">
15 <parent link="base_link"/>
16 <child link="link1_link"/>
17 <origin xyz="0 0 0" rpy="0 0 0"/>
18 <axis xyz="1 0 0"/>
19 <!--dynamics damping="0.7"/-->
20 <limit effort="100.0" velocity="100000" lower="-100000.0" upper="100000.0"/>
21 </joint>
22
23 <transmission name="transmission_base_link1">
24 <type>transmission_interface/SimpleTransmission</type>
25 <joint name="base_link1_joint">
26 <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
27 </joint>
28 <actuator name="link1_maxon_motor">
29 <hardwareInterface>EffortJointInterface</hardwareInterface>
30 <mechanicalReduction>1</mechanicalReduction>
31 </actuator>
32 </transmission>
33
34 </robot>
For a joint which is controlled in position you can set it to revolute type. If you have a joint controlled in velocity such as a wheel, you can set it to continuous type and remove the lower and upper limit:
1 <!-- Joint between Base link and Link1 link -->
2 <joint name="base_link1_joint" type="continuous">
3 <parent link="base_link"/>
4 <child link="link1_link"/>
5 <origin xyz="0 0 0" rpy="0 0 0"/>
6 <axis xyz="1 0 0"/>
7 <dynamics damping="0.7"/>
8 <limit effort="100.0" velocity="1300"/>
9 </joint>
The joint must be defined according to the one used in controller YAML file. It is possible to set a velocity limit and upper/lower position limits, which have to match with the units used in ROS and defined in the node YAML file. More information can be found here.
Launch file
In the launch folder you can create a launch file called maxon_epos4.launch and copy/paste the following content:
1 <?xml version="1.0"?>
2 <launch>
3 <group ns="/maxon">
4 <!-- Load the URDF into ROS parameter server -->
5 <param name="/maxon/robot_description" command="$(find xacro)/xacro '$(find epos4_canopen)/urdf/maxon_epos4.xacro'"/>
6
7 <node name="canopen_motor" pkg="canopen_motor_node" type="canopen_motor_node" output="screen" clear_params="true" >
8 <rosparam command="load" file="$(find epos4_canopen)/config/can.yaml" />
9 <rosparam command="load" file="$(find epos4_canopen)/config/controller.yaml" />
10 <rosparam command="load" file="$(find epos4_canopen)/config/node.yaml" />
11 </node>
12
13 <!-- load the controllers -->
14 <node name="controller_spawner" pkg="controller_manager" type="controller_manager" respawn="false"
15 output="screen" args="spawn
16 /maxon/canopen_motor/joint_state_controller
17 /maxon/canopen_motor/base_link1_joint_position_controller
18 "/>
19 </group>
20 </launch>
In case you are using a ROS Velocity Controller, you need to change the last argument of the controller_spawner node according to your controller.yaml file:
1 <node name="controller_spawner" pkg="controller_manager" type="controller_manager" respawn="false"
2 output="screen" args="spawn
3 /maxon/canopen_motor/joint_state_controller
4 /maxon/canopen_motor/base_link1_joint_velocity_controller
5 "/>
Basic demo
Once your ROS package is ready it is time to test it.
Installation
To install ros_canopen with its dependencies along with useful controller packages, install the following ROS packages (replace melodic with your ROS version name if necessary):
$ sudo apt-get install ros-melodic-canopen-* ros-melodic-control* ros-melodic-rqt-controller-manager ros-melodic-joint-state-controller ros-melodic-velocity-controllers ros-melodic-effort-controllers ros-melodic-joint-state-publisher-gui ros-melodic-std-srvs
Make sure your CAN interface is ready, and if not you can for example bring it up this way:
$ sudo /sbin/ip link set can0 up type can bitrate 1000000
Sending motor commands
Open a terminal and launch your launch file:
$ roslaunch epos4_canopen maxon_epos4.launch
In another terminal, call the initialization service of your driver:
$ rosservice call /maxon/driver/init
It should output "success: True" if it worked properly.
You can then send a command to the motor in a third terminal. This is done by publishing data on a controller topic.
If you have set a position controller, execute the following command, which will send a Target Position of 10000 inc (if “inc” is the chosen position unit on the ROS side as explained earlier) to the first node:
$ rostopic pub /maxon/canopen_motor/base_link1_joint_position_controller/command std_msgs/Float64 -- 10000
If you have set a velocity controller, execute the following command, which will send a Target Velocity of 500 rpm (if “rpm” is the chosen velocity unit on the ROS side as explained earlier) to the first node:
$ rostopic pub /maxon/canopen_motor/base_link1_joint_velocity_controller/command std_msgs/Float64 -- 500
Reading motor data
You can display in a terminal the content of the joint states using the echo command from rostopic:
$ rostopic echo /maxon/joint_states
It is published at the frequency chosen in the publishing_rate parameter of the joint_state_controller in the controller.yaml file.
Other services
You can halt, recover or shutdown the driver using the following services:
$ rosservice call /maxon/driver/halt $ rosservice call /maxon/driver/recover $ rosservice call /maxon/driver/shutdown
You can send SDO requests for setting and getting objects. For example, the following command sets the Profile Velocity (object 0x6081) of the joint “base_link1_joint” to the value of 1000 rpm:
$ rosservice call /maxon/driver/set_object base_link1_joint '!!str 6081' '!!str 1000' false
The following command gets the Profile Velocity value of the same node:
$ rosservice call /maxon/driver/get_object base_link1_joint '!!str 6081' false
To get (similarly set with set_object) the value of an object subindex you can do like that (example with Speed for Zero Search, object 0x6099 and subindex 0x02):
$ rosservice call /maxon/driver/get_object base_link1_joint 6099sub02 false
You can get the current state of each controller by calling the following service:
rosservice call /maxon/controller_manager/list_controllers
In this tutorial we saw how to connect maxon EPOS4 with ros_canopen, send motor commands for Profile Modes and read motor data. In the next tutorial we are going to use Cyclic Synchronous Operating Modes.