#include <ackermann_to_vesc.h>
Public Member Functions | |
AckermannToVesc (ros::NodeHandle nh, ros::NodeHandle private_nh) | |
Private Member Functions | |
void | ackermannCmdCallback (const ackermann_msgs::AckermannDriveStamped::ConstPtr &cmd) |
Private Attributes | |
ros::Subscriber | ackermann_sub_ |
ros::Publisher | erpm_pub_ |
ros::Publisher | servo_pub_ |
double | speed_to_erpm_gain_ |
double | speed_to_erpm_offset_ |
double | steering_to_servo_gain_ |
double | steering_to_servo_offset_ |
Definition at line 37 of file ackermann_to_vesc.h.
vesc_ackermann::AckermannToVesc::AckermannToVesc | ( | ros::NodeHandle | nh, |
ros::NodeHandle | private_nh | ||
) |
Definition at line 42 of file ackermann_to_vesc.cpp.
|
private |
Definition at line 63 of file ackermann_to_vesc.cpp.
|
private |
Definition at line 53 of file ackermann_to_vesc.h.
|
private |
Definition at line 51 of file ackermann_to_vesc.h.
|
private |
Definition at line 52 of file ackermann_to_vesc.h.
|
private |
Definition at line 45 of file ackermann_to_vesc.h.
|
private |
Definition at line 45 of file ackermann_to_vesc.h.
|
private |
Definition at line 46 of file ackermann_to_vesc.h.
|
private |
Definition at line 46 of file ackermann_to_vesc.h.