#include <riq_hand.h>
Public Types | |
enum | { PRODUCT_CODE = 11 } |
Public Member Functions | |
void | collectDiagnostics (EthercatCom *com) |
void | construct (EtherCAT_SlaveHandler *sh, int &start_address) |
void | diagnostics (diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *) |
int | initialize (pr2_hardware_interface::HardwareInterface *, bool) |
void | packCommand (unsigned char *buffer, bool halt, bool reset) |
RIQHand () | |
bool | unpackState (unsigned char *this_buffer, unsigned char *prev_buffer) |
~RIQHand () | |
Static Public Attributes | |
static const unsigned | COMMAND_PHY_ADDR = 0x1100 |
static const unsigned | COMMAND_SIZE = 12 |
static const unsigned | MBX_COMMAND_PHY_ADDR = 0x1000 |
static const unsigned | MBX_COMMAND_SIZE = 128 |
static const unsigned | MBX_STATUS_PHY_ADDR = 0x1080 |
static const unsigned | MBX_STATUS_SIZE = 128 |
static const unsigned | STATUS_PHY_ADDR = 0x1D00 |
static const unsigned | STATUS_SIZE = 12 |
Protected Member Functions | |
void | commandCallback (const riq_msgs::RIQHandCommand::ConstPtr &msg) |
Callback for ROS command. | |
unsigned | scaleAndSaturate255 (double value) |
Convert double in range of 0.0 to 1.0 to integer in range 0 to 255. | |
Static Protected Member Functions | |
static void | disableWatchdog (EtherCAT_SlaveHandler *sh) |
Diables ESC watchdog. | |
static void | sizeAssert () |
Asserts RIQHandStatus and RIQHandCommand match EtherCAT process data sizes. | |
Protected Attributes | |
int | after_reset_countdown_ |
Countdown timer for hand resets (re-initiailization) | |
int | after_watchdog_reset_countdown_ |
Countdown timer for watchdog timeout clear. | |
RIQHandDiagnostics | collect_diagnostics_ |
Structure where collected diagnostics are stored. | |
riq_msgs::RIQHandCommand | command_ |
Realtime loop cannot always get lock on command, so keep command msg available. | |
boost::mutex | command_mutex_ |
Use lock between command used in realtime thread, and those obtain from ros listener. | |
ros::Subscriber | commandSubscriber_ |
boost::mutex | diagnostics_mutex_ |
Protects collect_diagnostics_. | |
bool | halted_ |
True when device has halted (as requested by pr2_etherCAT hardware) | |
volatile unsigned | latched_fault_code_ |
Set by realtime thread when certain faults occur (faults that require reset-motors) | |
bool | needs_reset_ |
RIQ device need to go be sent reset when certain fault occur. | |
int | needs_reset_countdown_ |
Send reset command for a couple of cycles to make sure device sees it. | |
volatile bool | needs_watchdog_reset_ |
Set when watchdog reset is requested. | |
riq_msgs::RIQHandCommand | new_command_ |
Used for accepting command messages from ROS. | |
RIQHandDiagnostics | publish_diagnostics_ |
Copy of collected diagnostics for use by pubishing functions (run in a different thread) | |
realtime_tools::RealtimePublisher < riq_msgs::RIQHandState > | publisher_ |
Realtime publisher for RIQ Hand status data. | |
bool | should_publish_ |
Set to true when state message should be published. | |
unsigned | state_cycle_count_ |
Static Protected Attributes | |
static const unsigned | STATE_PUBLISH_PERIOD = 10 |
Definition at line 56 of file riq_hand.h.
anonymous enum |
Definition at line 78 of file riq_hand.h.
Definition at line 33 of file riq_hand.cpp.
Definition at line 47 of file riq_hand.cpp.
void riq_hand_ethercat_hardware::RIQHand::collectDiagnostics | ( | EthercatCom * | com | ) | [virtual] |
Reimplemented from EthercatDevice.
Definition at line 435 of file riq_hand.cpp.
void riq_hand_ethercat_hardware::RIQHand::commandCallback | ( | const riq_msgs::RIQHandCommand::ConstPtr & | msg | ) | [protected] |
Callback for ROS command.
Definition at line 194 of file riq_hand.cpp.
void riq_hand_ethercat_hardware::RIQHand::construct | ( | EtherCAT_SlaveHandler * | sh, |
int & | start_address | ||
) | [virtual] |
Reimplemented from EthercatDevice.
Definition at line 53 of file riq_hand.cpp.
void riq_hand_ethercat_hardware::RIQHand::diagnostics | ( | diagnostic_updater::DiagnosticStatusWrapper & | d, |
unsigned char * | buffer | ||
) | [virtual] |
Reimplemented from EthercatDevice.
Definition at line 488 of file riq_hand.cpp.
void riq_hand_ethercat_hardware::RIQHand::disableWatchdog | ( | EtherCAT_SlaveHandler * | sh | ) | [static, protected] |
Diables ESC watchdog.
Definition at line 415 of file riq_hand.cpp.
int riq_hand_ethercat_hardware::RIQHand::initialize | ( | pr2_hardware_interface::HardwareInterface * | , |
bool | |||
) | [virtual] |
Implements EthercatDevice.
Definition at line 176 of file riq_hand.cpp.
void riq_hand_ethercat_hardware::RIQHand::packCommand | ( | unsigned char * | buffer, |
bool | halt, | ||
bool | reset | ||
) | [virtual] |
Reimplemented from EthercatDevice.
Definition at line 210 of file riq_hand.cpp.
unsigned riq_hand_ethercat_hardware::RIQHand::scaleAndSaturate255 | ( | double | value | ) | [protected] |
Convert double in range of 0.0 to 1.0 to integer in range 0 to 255.
Definition at line 202 of file riq_hand.cpp.
void riq_hand_ethercat_hardware::RIQHand::sizeAssert | ( | ) | [static, protected] |
Asserts RIQHandStatus and RIQHandCommand match EtherCAT process data sizes.
Definition at line 27 of file riq_hand.cpp.
bool riq_hand_ethercat_hardware::RIQHand::unpackState | ( | unsigned char * | this_buffer, |
unsigned char * | prev_buffer | ||
) | [virtual] |
Reimplemented from EthercatDevice.
Definition at line 291 of file riq_hand.cpp.
int riq_hand_ethercat_hardware::RIQHand::after_reset_countdown_ [protected] |
Countdown timer for hand resets (re-initiailization)
Definition at line 142 of file riq_hand.h.
Countdown timer for watchdog timeout clear.
Definition at line 144 of file riq_hand.h.
Structure where collected diagnostics are stored.
Definition at line 112 of file riq_hand.h.
Realtime loop cannot always get lock on command, so keep command msg available.
Definition at line 106 of file riq_hand.h.
boost::mutex riq_hand_ethercat_hardware::RIQHand::command_mutex_ [protected] |
Use lock between command used in realtime thread, and those obtain from ros listener.
Definition at line 101 of file riq_hand.h.
const unsigned riq_hand_ethercat_hardware::RIQHand::COMMAND_PHY_ADDR = 0x1100 [static] |
Definition at line 68 of file riq_hand.h.
const unsigned riq_hand_ethercat_hardware::RIQHand::COMMAND_SIZE = 12 [static] |
Definition at line 69 of file riq_hand.h.
Definition at line 90 of file riq_hand.h.
boost::mutex riq_hand_ethercat_hardware::RIQHand::diagnostics_mutex_ [protected] |
Protects collect_diagnostics_.
Definition at line 114 of file riq_hand.h.
bool riq_hand_ethercat_hardware::RIQHand::halted_ [protected] |
True when device has halted (as requested by pr2_etherCAT hardware)
Definition at line 147 of file riq_hand.h.
volatile unsigned riq_hand_ethercat_hardware::RIQHand::latched_fault_code_ [protected] |
Set by realtime thread when certain faults occur (faults that require reset-motors)
Definition at line 134 of file riq_hand.h.
const unsigned riq_hand_ethercat_hardware::RIQHand::MBX_COMMAND_PHY_ADDR = 0x1000 [static] |
Definition at line 73 of file riq_hand.h.
const unsigned riq_hand_ethercat_hardware::RIQHand::MBX_COMMAND_SIZE = 128 [static] |
Definition at line 74 of file riq_hand.h.
const unsigned riq_hand_ethercat_hardware::RIQHand::MBX_STATUS_PHY_ADDR = 0x1080 [static] |
Definition at line 75 of file riq_hand.h.
const unsigned riq_hand_ethercat_hardware::RIQHand::MBX_STATUS_SIZE = 128 [static] |
Definition at line 76 of file riq_hand.h.
bool riq_hand_ethercat_hardware::RIQHand::needs_reset_ [protected] |
RIQ device need to go be sent reset when certain fault occur.
Definition at line 127 of file riq_hand.h.
int riq_hand_ethercat_hardware::RIQHand::needs_reset_countdown_ [protected] |
Send reset command for a couple of cycles to make sure device sees it.
Definition at line 129 of file riq_hand.h.
volatile bool riq_hand_ethercat_hardware::RIQHand::needs_watchdog_reset_ [protected] |
Set when watchdog reset is requested.
Definition at line 122 of file riq_hand.h.
Used for accepting command messages from ROS.
Definition at line 104 of file riq_hand.h.
Copy of collected diagnostics for use by pubishing functions (run in a different thread)
Definition at line 117 of file riq_hand.h.
realtime_tools::RealtimePublisher<riq_msgs::RIQHandState> riq_hand_ethercat_hardware::RIQHand::publisher_ [protected] |
Realtime publisher for RIQ Hand status data.
Definition at line 93 of file riq_hand.h.
bool riq_hand_ethercat_hardware::RIQHand::should_publish_ [protected] |
Set to true when state message should be published.
Definition at line 97 of file riq_hand.h.
unsigned riq_hand_ethercat_hardware::RIQHand::state_cycle_count_ [protected] |
Definition at line 94 of file riq_hand.h.
const unsigned riq_hand_ethercat_hardware::RIQHand::STATE_PUBLISH_PERIOD = 10 [static, protected] |
publish every 10 realtime cycles (10ms)
Definition at line 95 of file riq_hand.h.
const unsigned riq_hand_ethercat_hardware::RIQHand::STATUS_PHY_ADDR = 0x1D00 [static] |
Definition at line 70 of file riq_hand.h.
const unsigned riq_hand_ethercat_hardware::RIQHand::STATUS_SIZE = 12 [static] |
Definition at line 71 of file riq_hand.h.