42 #include <dll/ethercat_dll.h> 43 #include <al/ethercat_AL.h> 44 #include <dll/ethercat_device_addressed_telegram.h> 45 #include <dll/ethercat_frame.h> 47 #include <boost/crc.hpp> 48 #include <boost/static_assert.hpp> 66 EtherCAT_FMMU_Config *fmmu =
new EtherCAT_FMMU_Config(2);
68 (*fmmu)[0] = EC_FMMU(start_address,
81 (*fmmu)[1] = EC_FMMU(start_address,
91 start_address += base_status;
93 sh->set_fmmu_config(fmmu);
95 EtherCAT_PD_Config *pd =
new EtherCAT_PD_Config(4);
99 (*pd)[0].ChannelEnable =
true;
100 (*pd)[0].ALEventEnable =
true;
103 (*pd)[1].ChannelEnable =
true;
105 (*pd)[2] = EC_SyncMan(WGMailbox::MBX_COMMAND_PHY_ADDR, WGMailbox::MBX_COMMAND_SIZE, EC_QUEUED, EC_WRITTEN_FROM_MASTER);
106 (*pd)[2].ChannelEnable =
true;
107 (*pd)[2].ALEventEnable =
true;
109 (*pd)[3] = EC_SyncMan(WGMailbox::MBX_STATUS_PHY_ADDR, WGMailbox::MBX_STATUS_SIZE, EC_QUEUED);
110 (*pd)[3].ChannelEnable =
true;
112 sh->set_pd_config(pd);
134 double max_pwm_ratio = double(0x3C00) / double(
PWM_MAX);
135 double board_resistance = 0.8;
138 ROS_FATAL(
"Initializing motor trace failed");
unsigned int command_size_
void packCommand(unsigned char *buffer, bool halt, bool reset)
static const unsigned SIZE
EtherCAT driver for WG005 motor controller.
uint8_t board_major_
Printed circuit board revision (for this value 0=='A', 1=='B')
bool status_checksum_error_
static const unsigned STATUS_PHY_ADDR
void packCommand(unsigned char *buffer, bool halt, bool reset)
bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
PLUGINLIB_EXPORT_CLASS(WG05, EthercatDevice)
bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
int initialize(pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=true)
AppRamStatus app_ram_status_
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
bool initializeMotorModel(pr2_hardware_interface::HardwareInterface *hw, const string &device_description, double max_pwm_ratio, double board_resistance, bool poor_measured_motor_voltage)
Allocates and initialized motor trace for WG0X devices than use it (WG006, WG005) ...
unsigned int status_size_
bool verifyChecksum(const void *buffer, unsigned size)
static const unsigned COMMAND_PHY_ADDR
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
virtual int initialize(pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=true)