#include <vesc_driver.h>
Definition at line 44 of file vesc_driver.h.
Enumerator |
---|
MODE_INITIALIZING |
|
MODE_OPERATING |
|
Definition at line 86 of file vesc_driver.h.
void vesc_driver::VescDriver::brakeCallback |
( |
const std_msgs::Float64::ConstPtr & |
brake | ) |
|
|
private |
- Parameters
-
brake | Commanded 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
-
current | Commanded 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_cycle | Commanded 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
-
position | Commanded 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
-
servo | Commanded 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
-
speed | Commanded 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 |
void vesc_driver::VescDriver::vescErrorCallback |
( |
const std::string & |
error | ) |
|
|
private |
void vesc_driver::VescDriver::vescPacketCallback |
( |
const std::shared_ptr< VescPacket const > & |
packet | ) |
|
|
private |
driver state machine mode (state)
Definition at line 94 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.
The documentation for this class was generated from the following files: