Classes | Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
iqr::CasterHardware Class Reference

#include <caster_hardware_socketcan.h>

Inheritance diagram for iqr::CasterHardware:
Inheritance graph
[legend]

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::ControllerManagercontroller_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< ResourceManagerBaseinterface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

Detailed Description

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.

Member Enumeration Documentation

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.

Constructor & Destructor Documentation

iqr::CasterHardware::CasterHardware ( )

Initialize Caster hardware

Definition at line 12 of file caster_hardware_socketcan.cpp.

Member Function Documentation

void iqr::CasterHardware::CanReceiveCallback ( const can_msgs::Frame::ConstPtr &  msg)
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.

bool iqr::CasterHardware::Command ( RoboteqCanOpenObjectDictionary  query,
uint8_t  sub_index,
uint32_t  data,
uint8_t  data_length 
)
private

Definition at line 455 of file caster_hardware_socketcan.cpp.

bool iqr::CasterHardware::Connect ( )
void iqr::CasterHardware::ControllerCheck ( diagnostic_updater::DiagnosticStatusWrapper &  status)
private

Definition at line 212 of file caster_hardware_socketcan.cpp.

void iqr::CasterHardware::ControllerTimerCallback ( const ros::TimerEvent )
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.

void iqr::CasterHardware::LeftMotorCheck ( diagnostic_updater::DiagnosticStatusWrapper &  status)
private

Definition at line 83 of file caster_hardware_socketcan.cpp.

bool iqr::CasterHardware::Query ( RoboteqCanOpenObjectDictionary  query,
uint8_t  sub_index,
uint8_t  data_length 
)
private

Definition at line 449 of file caster_hardware_socketcan.cpp.

void iqr::CasterHardware::RegisterControlInterfaces ( )
private

Register interfaces with the RobotHW interface manager, allowing ros_control operation

Definition at line 380 of file caster_hardware_socketcan.cpp.

void iqr::CasterHardware::ResetTravelOffset ( )
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.

void iqr::CasterHardware::RightMotorCheck ( diagnostic_updater::DiagnosticStatusWrapper &  status)
private

Definition at line 124 of file caster_hardware_socketcan.cpp.

void iqr::CasterHardware::SendCanOpenData ( uint32_t  node_id,
RoboteqClientCommandType  type,
RoboteqCanOpenObjectDictionary  index,
uint8_t  sub_index,
uint32_t  data,
uint8_t  data_length 
)
private

Definition at line 416 of file caster_hardware_socketcan.cpp.

bool iqr::CasterHardware::SetDigitalOutputCB ( caster_base::SetDigitalOutput::Request &  req,
caster_base::SetDigitalOutput::Response &  res 
)
private

Definition at line 31 of file caster_hardware_socketcan.cpp.

void iqr::CasterHardware::StatusCheck ( diagnostic_updater::DiagnosticStatusWrapper &  status)
private

Definition at line 165 of file caster_hardware_socketcan.cpp.

std::string iqr::CasterHardware::ToBinary ( size_t  data,
uint8_t  length 
)
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.

Member Data Documentation

int iqr::CasterHardware::can_id_
private

Definition at line 134 of file caster_hardware_socketcan.h.

ros::Publisher iqr::CasterHardware::can_pub_
private

Definition at line 119 of file caster_hardware_socketcan.h.

ros::Subscriber iqr::CasterHardware::can_sub_
private

Definition at line 120 of file caster_hardware_socketcan.h.

controller_manager::ControllerManager* iqr::CasterHardware::controller_manager_
private

Definition at line 115 of file caster_hardware_socketcan.h.

diagnostic_updater::Updater iqr::CasterHardware::diagnostic_updater_
private

Definition at line 129 of file caster_hardware_socketcan.h.

int8_t iqr::CasterHardware::fault_flags_
private

Definition at line 139 of file caster_hardware_socketcan.h.

hardware_interface::JointStateInterface iqr::CasterHardware::joint_state_interface_
private

Definition at line 125 of file caster_hardware_socketcan.h.

struct iqr::CasterHardware::Joint iqr::CasterHardware::joints_[2]
private
std::string iqr::CasterHardware::left_wheel_joint_
private

Definition at line 122 of file caster_hardware_socketcan.h.

double iqr::CasterHardware::max_accel_
private

Definition at line 137 of file caster_hardware_socketcan.h.

double iqr::CasterHardware::max_speed_
private

Definition at line 137 of file caster_hardware_socketcan.h.

MotorStatus iqr::CasterHardware::motor_status_[2]
private

Definition at line 141 of file caster_hardware_socketcan.h.

ros::NodeHandle iqr::CasterHardware::nh_
private

Definition at line 111 of file caster_hardware_socketcan.h.

std::string iqr::CasterHardware::node_name_
private

Definition at line 109 of file caster_hardware_socketcan.h.

ros::NodeHandle iqr::CasterHardware::private_nh_
private

Definition at line 112 of file caster_hardware_socketcan.h.

std::string iqr::CasterHardware::receive_topic_
private

Definition at line 117 of file caster_hardware_socketcan.h.

std::string iqr::CasterHardware::right_wheel_joint_
private

Definition at line 122 of file caster_hardware_socketcan.h.

std::string iqr::CasterHardware::send_topic_
private

Definition at line 117 of file caster_hardware_socketcan.h.

ros::ServiceServer iqr::CasterHardware::set_io_service_
private

Definition at line 132 of file caster_hardware_socketcan.h.

int8_t iqr::CasterHardware::status_flags_
private

Definition at line 140 of file caster_hardware_socketcan.h.

ros::Timer iqr::CasterHardware::timer_
private

Definition at line 114 of file caster_hardware_socketcan.h.

hardware_interface::VelocityJointInterface iqr::CasterHardware::velocity_joint_interface_
private

Definition at line 126 of file caster_hardware_socketcan.h.

double iqr::CasterHardware::wheel_diameter_
private

Definition at line 137 of file caster_hardware_socketcan.h.


The documentation for this class was generated from the following files:


caster_base
Author(s): Ye Tian
autogenerated on Wed Dec 18 2019 03:34:39