ICube-Robotics / ethercat_driver_ros2

Hardware Interface for EtherCAT module integration with ros2_control
https://icube-robotics.github.io/ethercat_driver_ros2/
Apache License 2.0
156 stars 44 forks source link

Error Messages reading SDO Etherlab-EthercatMaster1.6 #136

Open NilsLo opened 4 months ago

NilsLo commented 4 months ago

By Reading SDOs 3 Errors occure:

  1. Wrong IOCTL-VERSION_MAGIC It is required to Set IOCTL_VERSION_MAGIC to 37 insted 31 in ec_master_async_io.hpp
  2. SDO-Read: Operation not Permitted In examples of IGH master.open(EcMasterAsync::ReadWrite); is used in upload function.
  3. Reading data as string: Failed to upload SDO: No buffer space available IGH uses
    
    if (data_type->byteSize){
    data.target_size = data_type->byteSize;
    } else{
    data.target_size = DefaultBufferSize;
    }
    data.target = new uint8_t[data.target_size + 1];
in upload function file ethercat_sdo_srv_server.cpp

with default buffer size:

const int DefaultBufferSize= 64 * 1024;


defined in data_convertion_tools.hpp
ibrahimsel commented 4 months ago

For 1. you could refer to #134

szliucm commented 2 weeks ago

I've faced the same problem: SDO-Read: Operation not Permitted. Have you solved it?

NilsLo commented 2 weeks ago

I've faced the same problem: SDO-Read: Operation not Permitted. Have you solved it?

Yes, I could solve it. I changed in: ethercat_sdo_srv_server.cpp

void upload(
...
-master.open(EcMasterAsync::Read);
+master.open(EcMasterAsync::ReadWrite);
...
szliucm commented 1 week ago

Thanks a lot for your solution.