Go to the documentation of this file.
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/static_assert.hpp>
65 EtherCAT_FMMU_Config *fmmu =
new EtherCAT_FMMU_Config(2);
67 (*fmmu)[0] = EC_FMMU(start_address,
80 (*fmmu)[1] = EC_FMMU(start_address,
90 start_address += base_status;
92 sh->set_fmmu_config(fmmu);
94 EtherCAT_PD_Config *pd =
new EtherCAT_PD_Config(4);
98 (*pd)[0].ChannelEnable =
true;
99 (*pd)[0].ALEventEnable =
true;
102 (*pd)[1].ChannelEnable =
true;
104 (*pd)[2] = EC_SyncMan(WGMailbox::MBX_COMMAND_PHY_ADDR, WGMailbox::MBX_COMMAND_SIZE, EC_QUEUED, EC_WRITTEN_FROM_MASTER);
105 (*pd)[2].ChannelEnable =
true;
106 (*pd)[2].ALEventEnable =
true;
108 (*pd)[3] = EC_SyncMan(WGMailbox::MBX_STATUS_PHY_ADDR, WGMailbox::MBX_STATUS_SIZE, EC_QUEUED);
109 (*pd)[3].ChannelEnable =
true;
111 sh->set_pd_config(pd);
133 double max_pwm_ratio = double(0x3C00) / double(
PWM_MAX);
134 double board_resistance = 0.8;
137 ROS_FATAL(
"Initializing motor trace failed");
bool verifyChecksum(const void *buffer, unsigned size)
int initialize(pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=true)
bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
static const unsigned STATUS_PHY_ADDR
bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
bool status_checksum_error_
PLUGINLIB_EXPORT_CLASS(WG05, EthercatDevice)
AppRamStatus app_ram_status_
EtherCAT driver for WG005 motor controller.
unsigned int status_size_
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
uint8_t board_major_
Printed circuit board revision (for this value 0=='A', 1=='B')
virtual int initialize(pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=true)
unsigned int command_size_
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)
void packCommand(unsigned char *buffer, bool halt, bool reset)
static const unsigned COMMAND_PHY_ADDR
void packCommand(unsigned char *buffer, bool halt, bool reset)
static const unsigned SIZE
ethercat_hardware
Author(s): Rob Wheeler
, Derek King
autogenerated on Thu Sep 26 2024 02:44:04