RIVeR-Lab / epos_hardware

Other
12 stars 39 forks source link

effort/current controller hardware interface #25

Closed indraneelpatil closed 6 years ago

indraneelpatil commented 6 years ago

Dear community, I am trying to set up a Maxon EC90 motor and an EPOS2 motor controller to work with ros_control. I have an effort controller implemented in ros_control and now I need a hardware interface to relay the torque commands to the motor via the EPOS2 controller!

Accordingly to the documentation, the EPOS2 controller has an additional current profile mode which can be used to implement controlled torque on the motor shaft.

As per my knowledge (which is fairly limited) epos_hardware ros package can only be used with the position profile mode and the velocity profile mode. I would like to request whosoever reads this post to guide me on how I should proceed with implementing a hardware interface for the effort controller mode for my EPOS controller.

Any form of help would be greatly appreciated! Warm Regards, Indraneel.

JimmyDaSilva commented 6 years ago

@indraneelpatil Not sure I understand what you didn't succeed to achieve, but here is an example of me setting up an effort_controller with ros_control and running the current profile on epos_hardware

Epos hardware configuration in the yaml: https://github.com/kuka-isir/lwr_peg_in_hole/blob/master/launch/screwdriver.yaml

URDF to declare the EffortJointInterface: https://github.com/kuka-isir/lwr_peg_in_hole/blob/master/launch/screwdriver.urdf#L19-L27

The launch file to start it all: https://github.com/kuka-isir/lwr_peg_in_hole/blob/master/launch/screwdriver.launch

indraneelpatil commented 6 years ago

@JimmyDaSilva Thank you so much for replying! I have been trying this for days! I followed exactly your instructions and implemented the three files (urdf, launch and parameter file): My parameter file (after inserting serial number and specifications according to my datasheet) looks like this :

# Time in seconds
# Current in amps
# position, velocity, and acceleration in device units
my_joint_actuator:
  actuator_name: 'test_joint_actuator'
  serial_number: '0x602079025628'
  operation_mode: 'current'
  clear_faults: true
  torque_constant: 70.5

  motor:
    type: 10
    ec_motor:
      nominal_current: 6.06
      max_output_current: 10.000
      thermal_time_constant: 234
      number_of_pole_pairs: 12

  sensor:
    type: 1
    incremental_encoder:
      resolution: 2048
      inverted_polarity: false

 # safety:
 #   max_following_error: 20000
 #   max_profile_velocity: 800
 #   max_acceleration: 10000

  #position_profile:
   # velocity: 100
    #acceleration: 80
    #deceleration: 35

  #velocity_profile:
  #  acceleration: 10000
  #  deceleration: 2000

But when I run the launch file, I get this error : [ERROR] [1530115774.657967792]: current is not a valid operation mode

Any suggestions? Thank you so much again!

JimmyDaSilva commented 6 years ago

Ah ^^. I forgot but there is a specific branch that has the current control: https://github.com/RIVeR-Lab/epos_hardware/tree/current_control

@mitchellwills Is there a reason why the current_control branch has not been merged to the master branches indigo-devel and kinetic-devel ?

indraneelpatil commented 6 years ago

@JimmyDaSilva Thank you so much! Using the current control branch resolved the error issue and now the launch file runs successfully. Now I have the same issue as you did earlier "the flashing LED actually sets to green and stops flashing, meaning its connected to the node, but sending effort command doesn't make the motor rotate" And the solution that you implemented hasn't solved my problem motor still doesnt rotate even if I publish float numbers on the effort command topic . Any ideas? Anything I am missing out on? Maybe my parameter .yaml file is wrong(the one that I have attached above)?

The /diagnostics topic shows the following data :

_key: "Commanded Torque" value: "500 Nm"

JimmyDaSilva commented 6 years ago

@indraneelpatil Yep I would go for the .yaml file. It took me a while to have it all working together too. Make sure you have specified the right parameters with respect to your datasheet

indraneelpatil commented 6 years ago

@JimmyDaSilva @mitchellwills Really sorry I am bothering you again! Need some guidance :( So I started from scratch and I reset the parameters and the regulation tuning using EPOS studio on windows! Then I changed the .yaml file exactly according to the data sheet.

Present Situation :

Possible Problems :

indraneelpatil commented 6 years ago

@JimmyDaSilva @mitchellwills The issue has been solved and current control is now working properly on my EPOS motor controller 24/5 and the EC90 Maxon motor.

The issue in the end as you predicted was with the torque_constant parameter in the yaml file. It was too low and hence the motor wouldn't rotate.

I would like to sincerely thank you guys for this amazing work you have done in making the Maxon motor hardware interface available to all of us. I am indebted to you guys!

JimmyDaSilva commented 6 years ago

@indraneelpatil Nice! I am glad it works now. Cheers, Jimmy