Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
vesc_driver::VescDriver Class Reference

#include <vesc_driver.h>

Classes

struct  CommandLimit
 

Public Member Functions

 VescDriver (ros::NodeHandle nh, ros::NodeHandle private_nh)
 

Private Types

enum  driver_mode_t { MODE_INITIALIZING, MODE_OPERATING }
 

Private Member Functions

void brakeCallback (const std_msgs::Float64::ConstPtr &brake)
 
void currentCallback (const std_msgs::Float64::ConstPtr &current)
 
void dutyCycleCallback (const std_msgs::Float64::ConstPtr &duty_cycle)
 
void positionCallback (const std_msgs::Float64::ConstPtr &position)
 
void servoCallback (const std_msgs::Float64::ConstPtr &servo)
 
void speedCallback (const std_msgs::Float64::ConstPtr &speed)
 
void timerCallback (const ros::TimerEvent &event)
 
void vescErrorCallback (const std::string &error)
 
void vescPacketCallback (const std::shared_ptr< VescPacket const > &packet)
 

Private Attributes

CommandLimit brake_limit_
 
ros::Subscriber brake_sub_
 
CommandLimit current_limit_
 
ros::Subscriber current_sub_
 
driver_mode_t driver_mode_
 driver state machine mode (state) More...
 
CommandLimit duty_cycle_limit_
 
ros::Subscriber duty_cycle_sub_
 
int fw_version_major_
 firmware major version reported by vesc More...
 
int fw_version_minor_
 firmware minor version reported by vesc More...
 
CommandLimit position_limit_
 
ros::Subscriber position_sub_
 
CommandLimit servo_limit_
 
ros::Publisher servo_sensor_pub_
 
ros::Subscriber servo_sub_
 
CommandLimit speed_limit_
 
ros::Subscriber speed_sub_
 
ros::Publisher state_pub_
 
ros::Timer timer_
 
VescInterface vesc_
 

Detailed Description

Definition at line 44 of file vesc_driver.h.

Member Enumeration Documentation

Enumerator
MODE_INITIALIZING 
MODE_OPERATING 

Definition at line 86 of file vesc_driver.h.

Constructor & Destructor Documentation

vesc_driver::VescDriver::VescDriver ( ros::NodeHandle  nh,
ros::NodeHandle  private_nh 
)

Definition at line 43 of file vesc_driver.cpp.

Member Function Documentation

void vesc_driver::VescDriver::brakeCallback ( const std_msgs::Float64::ConstPtr &  brake)
private
Parameters
brakeCommanded VESC braking current in Amps. Any value is accepted by this driver. However, note that the VESC may impose a more restrictive bounds on the range depending on its configuration.

Definition at line 217 of file vesc_driver.cpp.

void vesc_driver::VescDriver::currentCallback ( const std_msgs::Float64::ConstPtr &  current)
private
Parameters
currentCommanded VESC current in Amps. Any value is accepted by this driver. However, note that the VESC may impose a more restrictive bounds on the range depending on its configuration.

Definition at line 204 of file vesc_driver.cpp.

void vesc_driver::VescDriver::dutyCycleCallback ( const std_msgs::Float64::ConstPtr &  duty_cycle)
private
Parameters
duty_cycleCommanded VESC duty cycle. Valid range for this driver is -1 to +1. However, note that the VESC may impose a more restrictive bounds on the range depending on its configuration, e.g. absolute value is between 0.05 and 0.95.

Definition at line 191 of file vesc_driver.cpp.

void vesc_driver::VescDriver::positionCallback ( const std_msgs::Float64::ConstPtr &  position)
private
Parameters
positionCommanded VESC motor position in radians. Any value is accepted by this driver. Note that the VESC must be in encoder mode for this command to have an effect.

Definition at line 243 of file vesc_driver.cpp.

void vesc_driver::VescDriver::servoCallback ( const std_msgs::Float64::ConstPtr &  servo)
private
Parameters
servoCommanded VESC servo output position. Valid range is 0 to 1.

Definition at line 256 of file vesc_driver.cpp.

void vesc_driver::VescDriver::speedCallback ( const std_msgs::Float64::ConstPtr &  speed)
private
Parameters
speedCommanded VESC speed in electrical RPM. Electrical RPM is the mechanical RPM multiplied by the number of motor poles. Any value is accepted by this driver. However, note that the VESC may impose a more restrictive bounds on the range depending on its configuration.

Definition at line 231 of file vesc_driver.cpp.

void vesc_driver::VescDriver::timerCallback ( const ros::TimerEvent event)
private

Definition at line 107 of file vesc_driver.cpp.

void vesc_driver::VescDriver::vescErrorCallback ( const std::string &  error)
private

Definition at line 181 of file vesc_driver.cpp.

void vesc_driver::VescDriver::vescPacketCallback ( const std::shared_ptr< VescPacket const > &  packet)
private

Definition at line 146 of file vesc_driver.cpp.

Member Data Documentation

CommandLimit vesc_driver::VescDriver::brake_limit_
private

Definition at line 69 of file vesc_driver.h.

ros::Subscriber vesc_driver::VescDriver::brake_sub_
private

Definition at line 79 of file vesc_driver.h.

CommandLimit vesc_driver::VescDriver::current_limit_
private

Definition at line 68 of file vesc_driver.h.

ros::Subscriber vesc_driver::VescDriver::current_sub_
private

Definition at line 78 of file vesc_driver.h.

driver_mode_t vesc_driver::VescDriver::driver_mode_
private

driver state machine mode (state)

Definition at line 94 of file vesc_driver.h.

CommandLimit vesc_driver::VescDriver::duty_cycle_limit_
private

Definition at line 67 of file vesc_driver.h.

ros::Subscriber vesc_driver::VescDriver::duty_cycle_sub_
private

Definition at line 77 of file vesc_driver.h.

int vesc_driver::VescDriver::fw_version_major_
private

firmware major version reported by vesc

Definition at line 95 of file vesc_driver.h.

int vesc_driver::VescDriver::fw_version_minor_
private

firmware minor version reported by vesc

Definition at line 96 of file vesc_driver.h.

CommandLimit vesc_driver::VescDriver::position_limit_
private

Definition at line 71 of file vesc_driver.h.

ros::Subscriber vesc_driver::VescDriver::position_sub_
private

Definition at line 81 of file vesc_driver.h.

CommandLimit vesc_driver::VescDriver::servo_limit_
private

Definition at line 72 of file vesc_driver.h.

ros::Publisher vesc_driver::VescDriver::servo_sensor_pub_
private

Definition at line 76 of file vesc_driver.h.

ros::Subscriber vesc_driver::VescDriver::servo_sub_
private

Definition at line 82 of file vesc_driver.h.

CommandLimit vesc_driver::VescDriver::speed_limit_
private

Definition at line 70 of file vesc_driver.h.

ros::Subscriber vesc_driver::VescDriver::speed_sub_
private

Definition at line 80 of file vesc_driver.h.

ros::Publisher vesc_driver::VescDriver::state_pub_
private

Definition at line 75 of file vesc_driver.h.

ros::Timer vesc_driver::VescDriver::timer_
private

Definition at line 83 of file vesc_driver.h.

VescInterface vesc_driver::VescDriver::vesc_
private

Definition at line 52 of file vesc_driver.h.


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


vesc_driver
Author(s): Michael T. Boulet , Joshua Whitley
autogenerated on Sun Apr 18 2021 02:48:01