include
sr_edc_ethercat_drivers
sr0x.h
Go to the documentation of this file.
1
25
#ifndef SR_EDC_ETHERCAT_DRIVERS_SR0X_H
26
#define SR_EDC_ETHERCAT_DRIVERS_SR0X_H
27
28
#include <ros_ethercat_hardware/ethercat_hardware.h>
29
#include <
sr_edc_ethercat_drivers/motor_trace_buffer.h
>
30
#include <string>
31
32
class
SR0X
:
33
public
EthercatDevice
34
{
35
public
:
36
virtual
int
initialize
(hardware_interface::HardwareInterface *hw,
bool
allow_unprogrammed =
true
);
37
38
protected
:
39
uint8_t
fw_major_
;
40
uint8_t
fw_minor_
;
41
uint8_t
board_major_
;
42
uint8_t
board_minor_
;
43
44
enum
45
{
46
MODE_OFF
= 0x00,
47
MODE_ENABLE
= (1 << 0),
48
MODE_CURRENT
= (1 << 1),
49
MODE_SAFETY_RESET
= (1 << 4),
50
MODE_SAFETY_LOCKOUT
= (1 << 5),
51
MODE_UNDERVOLTAGE
= (1 << 6),
52
MODE_RESET
= (1 << 7)
53
};
54
55
enum
56
{
57
EC_PRODUCT_ID_BRIDGE
= 0,
58
EC_PRODUCT_ID_SHADOWCAN
= 2,
59
EC_PRODUCT_ID_DUALMOTOR
= 3,
60
};
61
62
string
reason_
;
63
int
level_
;
64
int
device_offset_
;
// !< Offset of device position from first device of Shadow Hand
65
66
protected
:
67
int
command_base_
;
68
int
status_base_
;
69
};
70
71
#endif // SR_EDC_ETHERCAT_DRIVERS_SR0X_H
72
SR0X::MODE_ENABLE
Definition:
sr0x.h:47
SR0X::EC_PRODUCT_ID_SHADOWCAN
Definition:
sr0x.h:58
SR0X::initialize
virtual int initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed=true)
Definition:
sr0x.cpp:36
SR0X::MODE_SAFETY_LOCKOUT
Definition:
sr0x.h:50
SR0X::device_offset_
int device_offset_
Definition:
sr0x.h:64
SR0X::command_base_
int command_base_
Definition:
sr0x.h:67
SR0X::EC_PRODUCT_ID_BRIDGE
Definition:
sr0x.h:57
SR0X::fw_major_
uint8_t fw_major_
Definition:
sr0x.h:39
SR0X::reason_
string reason_
Definition:
sr0x.h:62
SR0X::fw_minor_
uint8_t fw_minor_
Definition:
sr0x.h:40
SR0X::board_major_
uint8_t board_major_
Definition:
sr0x.h:41
SR0X::MODE_CURRENT
Definition:
sr0x.h:48
SR0X::level_
int level_
Definition:
sr0x.h:63
SR0X::MODE_OFF
Definition:
sr0x.h:46
SR0X::MODE_SAFETY_RESET
Definition:
sr0x.h:49
SR0X
Definition:
sr0x.h:32
motor_trace_buffer.h
Publishes the last second of the motor controller.
SR0X::board_minor_
uint8_t board_minor_
Definition:
sr0x.h:42
SR0X::MODE_UNDERVOLTAGE
Definition:
sr0x.h:51
SR0X::EC_PRODUCT_ID_DUALMOTOR
Definition:
sr0x.h:59
SR0X::MODE_RESET
Definition:
sr0x.h:52
SR0X::status_base_
int status_base_
Definition:
sr0x.h:68
sr_edc_ethercat_drivers
Author(s): Ugo Cupcic, Yann Sionneau, Toni Oliver
autogenerated on Mon Feb 28 2022 23:50:53