ros-industrial / ros_canopen

CANopen driver framework for ROS (http://wiki.ros.org/ros_canopen)
GNU Lesser General Public License v3.0
339 stars 271 forks source link

Cannot switch to profile velocity mode after initialization #328

Open ishugoel20 opened 5 years ago

ishugoel20 commented 5 years ago

Hi,

I am working with engel can motor and after initializing the motor with driver/init service, I cannot switch the mode to profile velocity mode. I get the error that 'mode does not match'. On debugging the can log, I found that the halt bit is set to '1' after the finish of init service which prevents the controller from switching modes.

If I set the Halt bit to '0' in line 416 of motor.cpp inside the function Motor402::handleWrite, I can switch mode to velocity and provide velocity values. I do not know if this is good fix for this problem? Should I change the halt bit using a parameter? Is there any other way to solve this problem?

Kindly provide suggestions for the same.

Thanks, Ishu

mathias-luedtke commented 5 years ago

The Halt bit is crucial for safe operation and control, you should not remove it. You might use a different switching state (in your config):

  motor_layer: settings passed to motor layer (plugin-specific)
    switching_state: 5 # (Operation_Enable), state for mode switching

You can find the values in this enum.

According to the 402 standard the state is vendor-specific. You drive's manual might list the correct state.

ishugoel20 commented 5 years ago

@ipa-mdl Thanks for your response. I already tried that solution, it did not work.

In the datasheet of the motor at page no. 38 , it clearly mentions that "Changing the mode of operation is not allowed, when the HALT-bit (Bit 8 of Controlword6040h, chapter 5.3.1) is set!".

If I create a variable which can be used to set or reset the Halt bit based on the motor, will it be an acceptable change? Also, is it possible to change the default value of Modes of Operation from 1 (Profile Position Mode) to 3 (Profile Velocity Mode)?

mathias-luedtke commented 5 years ago

If I create a variable which can be used to set or reset the Halt bit based on the motor, will it be an acceptable change?

I would suggest to reset the Halt bit as long as the motor operation is not enabled and or is not in any mode (#331 ). Toggling the halt bit in operation-enabled mode is not safe while switching modes.

Also, is it possible to change the default value of Modes of Operation from 1 (Profile Position Mode) to 3 (Profile Velocity Mode)?

Just set specify the parameter in your DCF/EDS or dcf_overlay.

mzahana commented 2 years ago

@ishugoel20 Hi! Where you able to change the default mode of operation to Profile Velocity?