calssicladder and ethercat

More
09 Apr 2022 16:24 #239748 by db1981
Replied by db1981 on topic calssicladder and ethercat
seems that there are a few understanding problems....

lcec is not starting, caused of an pdo config error.

-reading your xml , i notice that your drives are identical. You now have used the example pdo config from cia example for slave 1, but if the drive is identical to drive 0, you have to use the right pdo config like drive 0 ....

-for using the cia component, you have to be shure that your drives are cia402 compatible. For this you would need the pdos for "modes_of_operation" and "modes_of_operation_display" . may be this has to be configured in the drive himself. What types of drives are this?

-old_style / cia_style There exists no style.... your ethercat config xml has to match to your hardware. The Cia Component is only an Interface block between the ethercat_drivers hal pins, and linuxcnc hal pins. So if your name your pdo for statusword in the XML "xxasdf" and connect this name in the hal to the statusword input of the cia component , all is fine.
The following user(s) said Thank You: bkt

Please Log in or Create an account to join the conversation.

More
10 Apr 2022 11:45 #239811 by bkt
Replied by bkt on topic calssicladder and ethercat
so you means same drive same var type ... slave "0" work perfect with generc drive as mine ... and slave "1" the same .... so I use cia402 on slave "1" only ... actually I change xml in these manner:
<masters>
<master idx="0" appTimePeriod="2000000" refClockSyncCycles="1">
  <slave idx="0" type="generic" vid="000007DD" pid="01" configPdos="true">
    <sdoConfig idx="6060" subIdx="0"><sdoDataRaw data="08"/></sdoConfig>
    <sdoConfig idx="60C2" subIdx="1"><sdoDataRaw data="01"/></sdoConfig>
    <sdoConfig idx="60C2" subIdx="2"><sdoDataRaw data="FD"/></sdoConfig>
    <sdoConfig idx="607E" subIdx="0"><sdoDataRaw data="E0"/></sdoConfig>
    <syncManager idx="0" dir="out"></syncManager>
    <syncManager idx="1" dir="in"></syncManager>
    <syncManager idx="2" dir="out">
      <pdo idx="1601">
        <pdoEntry idx="6040" subIdx="00" bitLen="16" halPin="driverControl" halType="bit"/>
        <pdoEntry idx="607A" subIdx="00" bitLen="32" halPin="posCommand" halType="float" scale="71750"/>
      </pdo>
    </syncManager>
    <syncManager idx="3" dir="in">
      <pdo idx="1A01">
        <pdoEntry idx="603F" subIdx="00" bitLen="16" halPin="errorStat" halType="bit"/>
        <pdoEntry idx="6041" subIdx="00" bitLen="16" halPin="driverStatus" halType="bit"/>
        <pdoEntry idx="6064" subIdx="00" bitLen="32" halPin="posActual" halType="float" scale="0.000013937"/>
        <pdoEntry idx="606C" subIdx="00" bitLen="32" halPin="velActual" halType="float" scale="0.000013937"/>
        <pdoEntry idx="6077" subIdx="00" bitLen="16" halPin="torkStat" halType="float" scale="0.1"/>
      </pdo>
    </syncManager>
    <dcConf assignActivate="300" sync0Cycle="*1" sync0Shift="500000"/>
    <slave idx="1" type="generic" vid="000007DD" pid="01" configPdos="true">
      <dcConf assignActivate="300" sync0Cycle="*1" sync0Shift="0"/>
      <syncManager idx="2" dir="out">
        <pdo idx="1601">
          <pdoEntry idx="6040" subIdx="00" bitLen="16" halPin="cia-controlword" halType="bit"/>
          <!-- <pdoEntry idx="6060" subIdx="00" bitLen="8" halPin="opmode" halType="s32"/> -->
          <pdoEntry idx="607A" subIdx="00" bitLen="32" halPin="target-position" halType="float"/>
          <!-- <pdoEntry idx="60FF" subIdx="00" bitLen="32" halPin="target-velocity" halType="s32"/> -->
        </pdo>
      </syncManager>
      <syncManager idx="3" dir="in">
        <pdo idx="1a01">
          <pdoEntry idx="603F" subIdx="00" bitLen="16" halPin="cia-errorStat" halType="bit"/>
          <pdoEntry idx="6041" subIdx="00" bitLen="16" halPin="cia-statusword" halType="bit"/>
          <pdoEntry idx="6064" subIdx="00" bitLen="32" halPin="actual-position" halType="float"/>
          <pdoEntry idx="606C" subIdx="00" bitLen="32" halPin="actual-velocity" halType="float"/>
          <pdoEntry idx="6077" subIdx="00" bitLen="32" halPin="actual-torque" halType="float"/>
        </pdo>
      </syncManager>
    </slave>

In any case I am trying to use cia402 for the sole purpose of being able to use joint.0 (slave "0") as a normal axis while I want to use slave "1" as a positioner that can be moved at any time by classicladder also when joint.0 is in motion .... this is the purpose of the whole .... I clarify it because I would not like to have embarked on a path that does not lead to the result.

In any case, many thanks for your help.

bkt

Please Log in or Create an account to join the conversation.

More
10 Apr 2022 11:55 - 10 Apr 2022 12:09 #239815 by bkt
Replied by bkt on topic calssicladder and ethercat
AFTER THAT CHANGE and addin a missing </slave>:

Lcnc start ... but need to change some pin name .... I see in some point I use old name and not "cia-xxxx" as my xml .....

I understand that CIA402 make the right pin from drive to Lcnc and facilitate SCALE usage ... but things was a rapid way for unlock slave1 from joint.n control .... so mine is only an error?

regards
bkt
Last edit: 10 Apr 2022 12:09 by bkt.

Please Log in or Create an account to join the conversation.

More
10 Apr 2022 14:06 #239825 by db1981
Replied by db1981 on topic calssicladder and ethercat
if all slaves goes to "ethercat op state" again after startup, this would be the first step.

now, in theory you would be able to to control the axis manualy:

-set the scale value for the cia component.
-link the output from simple_tp to the pos_cmd input of the cia-comp
-create an net e.g aux-enable and link it to enable from simple_tp and cia-comp

if you now manualy setp the aux-enable pin , your driver should get enabled.

If this works, you can setp the pos input from simple tp and the axis should drive to the desired position.

Please Log in or Create an account to join the conversation.

More
10 Apr 2022 14:10 - 10 Apr 2022 14:10 #239826 by db1981
Replied by db1981 on topic calssicladder and ethercat
Note:

please set this pos in mind in front of the last post....

It is important to get access to the mode of operations pdos from your drive. You have to find out how you can add them to your ethercat configuration. This will be an drive config thing......
Without this cia-comp won't be usable and homing could get a mess....
Last edit: 10 Apr 2022 14:10 by db1981.

Please Log in or Create an account to join the conversation.

More
11 Apr 2022 04:42 #239880 by bkt
Replied by bkt on topic calssicladder and ethercat
think change operation mode during normal run, if these is what you means, in my drive is not possible. I have only csp, csv, and hm (for internal homing and touch probe operation) .... no other avaiable. But to be sure I've to try
pdos access in reading mode is for sure avaiable.
about scale in cia .... because I've scale in right manner on xml, I use scale=1 in cia comp. These can be?

Your intention is to run hm mode (for homing pourpuse) and after csp mode? These is the goal?


plus simple_tp can be menage without cia402 comp .... but .... when run simple_tp command pos and during motion I start an MDI command for slave0, slave1 stop motion immediately but MDI run and continue ..... I hope with cia402 these ca be solved .... Is the right way to solve these ?

Please Log in or Create an account to join the conversation.

More
11 Apr 2022 08:47 #239904 by db1981
Replied by db1981 on topic calssicladder and ethercat
i've checked source code of simple tp. There is no relationship to motion/mdi or other parts. This is a standalone component.

This must be an hal error, but is not related to cia.

simple_tp has to work standalone....

How can you change the modes of your drives beetween csp, csc, homing ?
The following user(s) said Thank You: bkt

Please Log in or Create an account to join the conversation.

More
12 Apr 2022 04:31 #240010 by bkt
Replied by bkt on topic calssicladder and ethercat

i've checked source code of simple tp. There is no relationship to motion/mdi or other parts. This is a standalone componen

How can you change the modes of your drives beetween csp, csc, homing ?

I think i need to dis-enable and enable again ..... but today I try and report here the result .....but if simple_tp is standalone componenet cia402 really need to me? These is not understand well untill now.

regards
bkt

Please Log in or Create an account to join the conversation.

More
12 Apr 2022 06:06 #240015 by db1981
Replied by db1981 on topic calssicladder and ethercat
my intention to use cia was only to get an easy homing solution. But if your drives not full cia compatible and do not have the modes_of_operation stuff ,
it would be useless ....
The following user(s) said Thank You: bkt

Please Log in or Create an account to join the conversation.

More
12 Apr 2022 06:37 #240017 by rodw
Replied by rodw on topic calssicladder and ethercat

my intention to use cia was only to get an easy homing solution. But if your drives not full cia compatible and do not have the modes_of_operation stuff ,
it would be useless ....

I'm hoping to develop a user installable homing module specific for cia402 drives using your work but the pins in your component will migrate to the joints themselves. We should be able to chain off the read_homing_in_pins() and write_homing_out_pins() procedures if I understand the homing.code. Very cool enhancement to master branch by Dewey Garrett alows this!

Please Log in or Create an account to join the conversation.

Time to create page: 0.107 seconds
Powered by Kunena Forum