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);
134 for (
size_t i = 0; i <
sizeof(digital_outs)/
sizeof(digital_outs[0]); ++i)
139 ROS_FATAL(
"A digital out of the name '%s' already exists. Device #%02d has a duplicate name", digital_outs[i].
d->name_.c_str(),
sh_->get_ring_position());
149 ROS_FATAL(
"A projector of the name '%s' already exists. Device #%02d has a duplicate name",
projector_.
name_.c_str(),
sh_->get_ring_position());
181 c->
config0_ = ((cmd.
A_ & 0xf) << 4) | ((cmd.
B_ & 0xf) << 0);
182 c->
config1_ = ((cmd.
I_ & 0xf) << 4) | ((cmd.
M_ & 0xf) << 0);
215 state.
A_ = ((this_status->
config0_ >> 4) & 0xf);
216 state.
B_ = ((this_status->
config0_ >> 0) & 0xf);
217 state.
I_ = ((this_status->
config1_ >> 4) & 0xf);
218 state.
M_ = ((this_status->
config1_ >> 0) & 0xf);
251 d.hardware_id = serial;
258 d.
addf(
"Position",
"%02d",
sh_->get_ring_position());
259 d.
addf(
"Product code",
260 "WG021 (%d) Firmware Revision %d.%02d, PCB Revision %c.%02d",
265 d.
add(
"Serial Number", serial);
int16_t measured_current_
uint16_t max_bridge_temperature_
ProjectorCommand command_
double last_measured_current_
unsigned int command_size_
pr2_hardware_interface::DigitalOut digital_out_L0_
void publishMailboxDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &d)
void publishGeneralDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &d)
static string modeString(uint8_t mode)
void summary(unsigned char lvl, const std::string s)
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
uint32_t rising_timestamp_us_
bool falling_timestamp_valid_
unsigned computeChecksum(void const *data, unsigned length)
void ethercatDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned numPorts)
Adds diagnostic information for EtherCAT ports.
pr2_hardware_interface::Projector projector_
uint16_t board_temperature_
pr2_hardware_interface::DigitalOut digital_out_B_
pr2_hardware_interface::DigitalOut digital_out_I_
uint8_t board_major_
Printed circuit board revision (for this value 0=='A', 1=='B')
float nominal_voltage_scale_
uint32_t falling_timestamp_us_
bool status_checksum_error_
static const unsigned SIZE
static const unsigned STATUS_PHY_ADDR
pr2_hardware_interface::DigitalOut digital_out_
uint8_t board_minor_
Printed circuit assembly revision.
void addf(const std::string &key, const char *format,...)
int16_t programmed_current_
void clearErrorFlags(void)
bool verifyState(WG0XStatus *this_status, WG0XStatus *prev_status)
unsigned int rotateRight8(unsigned in)
uint16_t absolute_current_limit_
double last_executed_current_
uint8_t configuration_status_
double last_commanded_current_
WG0XConfigInfo config_info_
double max_current_
min(board current limit, actuator current limit)
EtherCAT_SlaveHandler * sh_
bool addProjector(Projector *projector)
pr2_hardware_interface::DigitalOut digital_out_A_
uint16_t bridge_temperature_
PLUGINLIB_EXPORT_CLASS(WG021, EthercatDevice)
AppRamStatus app_ram_status_
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
uint32_t device_serial_number_
float nominal_current_scale_
uint16_t max_board_temperature_
unsigned int status_size_
void packCommand(unsigned char *buffer, bool halt, bool reset)
int16_t programmed_current_
bool verifyChecksum(const void *buffer, unsigned size)
pr2_hardware_interface::DigitalOut digital_out_M_
pr2_hardware_interface::DigitalOut digital_out_L1_
ethercat_hardware::WGMailbox mailbox_
Mailbox access to device.
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *)
For EtherCAT device that only publish one EtherCAT Status message. If sub-class implements multiDiagn...
static const unsigned COMMAND_PHY_ADDR
void add(const std::string &key, const T &val)
uint32_t output_start_timestamp_
static double min(double a, double b)
bool rising_timestamp_valid_
DigitalOutCommand command_
int initialize(pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=true)
bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
uint32_t output_stop_timestamp_
virtual int initialize(pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=true)
bool addDigitalOut(DigitalOut *digital_out)
WG0XActuatorInfo actuator_info_