#include <caster_hardware_socketcan.h>

| Classes | |
| struct | Joint | 
| struct | MotorStatus | 
| Public Types | |
| enum | MotorIndex { kLeftMotor = 0x00, kRightMotor = 0x01 } | 
| enum | RoboteqCanOpenObjectDictionary { kSetVelocity = 0x2002, kSetBLCounter = 0x2004, kSetIndividualDO = 0x2009, kResetIndividualDO = 0x200A, kReadMotorAmps = 0x2100, kReadAbsBLCounter = 0x2105, kReadBLMotorRPM = 0x210A, kReadStatusFlags = 0x2111, kReadFaultFlags = 0x2112, kReadMotorStatusFlags = 0x2122 } | 
| enum | RoboteqClientCommandType { kCommand = 0x02, kQuery = 0x04, kResponseCommandSuccess = 0x06, kResponseMessageError = 0x08 } | 
| Public Member Functions | |
| CasterHardware () | |
| void | Clear () | 
| bool | Connect () | 
| void | Initialize (std::string node_name, ros::NodeHandle &nh, ros::NodeHandle &private_nh) | 
| void | UpdateHardwareStatus () | 
| void | WriteCommandsToHardware () | 
|  Public Member Functions inherited from hardware_interface::RobotHW | |
| virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const | 
| virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const | 
| virtual void | doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) | 
| virtual void | doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) | 
| virtual bool | init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) | 
| virtual bool | prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list) | 
| virtual bool | prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list) | 
| virtual void | read (const ros::Time &time, const ros::Duration &period) | 
| virtual void | read (const ros::Time &time, const ros::Duration &period) | 
| RobotHW () | |
| virtual void | write (const ros::Time &time, const ros::Duration &period) | 
| virtual void | write (const ros::Time &time, const ros::Duration &period) | 
| virtual | ~RobotHW () | 
|  Public Member Functions inherited from hardware_interface::InterfaceManager | |
| T * | get () | 
| std::vector< std::string > | getInterfaceResources (std::string iface_type) const | 
| std::vector< std::string > | getNames () const | 
| void | registerInterface (T *iface) | 
| void | registerInterfaceManager (InterfaceManager *iface_man) | 
| Private Member Functions | |
| void | CanReceiveCallback (const can_msgs::Frame::ConstPtr &msg) | 
| bool | Command (RoboteqCanOpenObjectDictionary query, uint8_t sub_index, uint32_t data, uint8_t data_length) | 
| void | ControllerCheck (diagnostic_updater::DiagnosticStatusWrapper &status) | 
| void | ControllerTimerCallback (const ros::TimerEvent &) | 
| void | LeftMotorCheck (diagnostic_updater::DiagnosticStatusWrapper &status) | 
| bool | Query (RoboteqCanOpenObjectDictionary query, uint8_t sub_index, uint8_t data_length) | 
| void | RegisterControlInterfaces () | 
| void | ResetTravelOffset () | 
| void | RightMotorCheck (diagnostic_updater::DiagnosticStatusWrapper &status) | 
| void | SendCanOpenData (uint32_t node_id, RoboteqClientCommandType type, RoboteqCanOpenObjectDictionary index, uint8_t sub_index, uint32_t data, uint8_t data_length) | 
| bool | SetDigitalOutputCB (caster_base::SetDigitalOutput::Request &req, caster_base::SetDigitalOutput::Response &res) | 
| void | StatusCheck (diagnostic_updater::DiagnosticStatusWrapper &status) | 
| std::string | ToBinary (size_t data, uint8_t length) | 
| Private Attributes | |
| int | can_id_ | 
| ros::Publisher | can_pub_ | 
| ros::Subscriber | can_sub_ | 
| controller_manager::ControllerManager * | controller_manager_ | 
| diagnostic_updater::Updater | diagnostic_updater_ | 
| int8_t | fault_flags_ | 
| hardware_interface::JointStateInterface | joint_state_interface_ | 
| struct iqr::CasterHardware::Joint | joints_ [2] | 
| std::string | left_wheel_joint_ | 
| double | max_accel_ | 
| double | max_speed_ | 
| MotorStatus | motor_status_ [2] | 
| ros::NodeHandle | nh_ | 
| std::string | node_name_ | 
| ros::NodeHandle | private_nh_ | 
| std::string | receive_topic_ | 
| std::string | right_wheel_joint_ | 
| std::string | send_topic_ | 
| ros::ServiceServer | set_io_service_ | 
| int8_t | status_flags_ | 
| ros::Timer | timer_ | 
| hardware_interface::VelocityJointInterface | velocity_joint_interface_ | 
| double | wheel_diameter_ | 
| Additional Inherited Members | |
|  Protected Types inherited from hardware_interface::InterfaceManager | |
| typedef std::vector< InterfaceManager * > | InterfaceManagerVector | 
| typedef std::map< std::string, void * > | InterfaceMap | 
| typedef std::map< std::string, std::vector< std::string > > | ResourceMap | 
| typedef std::map< std::string, size_t > | SizeMap | 
|  Protected Attributes inherited from hardware_interface::InterfaceManager | |
| boost::ptr_vector< ResourceManagerBase > | interface_destruction_list_ | 
| InterfaceManagerVector | interface_managers_ | 
| InterfaceMap | interfaces_ | 
| InterfaceMap | interfaces_combo_ | 
| SizeMap | num_ifaces_registered_ | 
| ResourceMap | resources_ | 
Class representing Caster hardware, allows for ros_control to modify internal state via joint interfaces
Definition at line 35 of file caster_hardware_socketcan.h.
| Enumerator | |
|---|---|
| kLeftMotor | |
| kRightMotor | |
Definition at line 47 of file caster_hardware_socketcan.h.
| Enumerator | |
|---|---|
| kSetVelocity | |
| kSetBLCounter | |
| kSetIndividualDO | |
| kResetIndividualDO | |
| kReadMotorAmps | |
| kReadAbsBLCounter | |
| kReadBLMotorRPM | |
| kReadStatusFlags | |
| kReadFaultFlags | |
| kReadMotorStatusFlags | |
Definition at line 59 of file caster_hardware_socketcan.h.
| Enumerator | |
|---|---|
| kCommand | |
| kQuery | |
| kResponseCommandSuccess | |
| kResponseMessageError | |
Definition at line 52 of file caster_hardware_socketcan.h.
| iqr::CasterHardware::CasterHardware | ( | ) | 
Initialize Caster hardware
Definition at line 12 of file caster_hardware_socketcan.cpp.
| 
 | private | 
Definition at line 251 of file caster_hardware_socketcan.cpp.
| void iqr::CasterHardware::Clear | ( | ) | 
Definition at line 313 of file caster_hardware_socketcan.cpp.
| 
 | private | 
Definition at line 455 of file caster_hardware_socketcan.cpp.
| bool iqr::CasterHardware::Connect | ( | ) | 
| 
 | private | 
Definition at line 212 of file caster_hardware_socketcan.cpp.
| 
 | private | 
Definition at line 25 of file caster_hardware_socketcan.cpp.
| void iqr::CasterHardware::Initialize | ( | std::string | node_name, | 
| ros::NodeHandle & | nh, | ||
| ros::NodeHandle & | private_nh | ||
| ) | 
Definition at line 50 of file caster_hardware_socketcan.cpp.
| 
 | private | 
Definition at line 83 of file caster_hardware_socketcan.cpp.
| 
 | private | 
Definition at line 449 of file caster_hardware_socketcan.cpp.
| 
 | private | 
Register interfaces with the RobotHW interface manager, allowing ros_control operation
Definition at line 380 of file caster_hardware_socketcan.cpp.
| 
 | private | 
Get current encoder travel offsets from MCU and bias future encoder readings against them
Definition at line 373 of file caster_hardware_socketcan.cpp.
| 
 | private | 
Definition at line 124 of file caster_hardware_socketcan.cpp.
| 
 | private | 
Definition at line 416 of file caster_hardware_socketcan.cpp.
| 
 | private | 
Definition at line 31 of file caster_hardware_socketcan.cpp.
| 
 | private | 
Definition at line 165 of file caster_hardware_socketcan.cpp.
| 
 | private | 
Definition at line 16 of file caster_hardware_socketcan.cpp.
| void iqr::CasterHardware::UpdateHardwareStatus | ( | ) | 
Definition at line 321 of file caster_hardware_socketcan.cpp.
| void iqr::CasterHardware::WriteCommandsToHardware | ( | ) | 
Definition at line 397 of file caster_hardware_socketcan.cpp.
| 
 | private | 
Definition at line 134 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 119 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 120 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 115 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 129 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 139 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 125 of file caster_hardware_socketcan.h.
| 
 | private | 
| 
 | private | 
Definition at line 122 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 137 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 137 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 141 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 111 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 109 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 112 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 117 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 122 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 117 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 132 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 140 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 114 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 126 of file caster_hardware_socketcan.h.
| 
 | private | 
Definition at line 137 of file caster_hardware_socketcan.h.