#include <vesc_to_odom.h>
Definition at line 42 of file vesc_to_odom.h.
void vesc_ackermann::VescToOdom::servoCmdCallback |
( |
const std_msgs::Float64::ConstPtr & |
servo | ) |
|
|
private |
void vesc_ackermann::VescToOdom::vescStateCallback |
( |
const vesc_msgs::VescStateStamped::ConstPtr & |
state | ) |
|
|
private |
- Todo:
- could probably do better propigating odometry, e.g. trapezoidal integration
- Todo:
- Think about position uncertainty, perhaps get from parameters?
< x
< y
< yaw
- Todo:
- Think about velocity uncertainty
Definition at line 83 of file vesc_to_odom.cpp.
std::string vesc_ackermann::VescToOdom::base_frame_ |
|
private |
std_msgs::Float64::ConstPtr vesc_ackermann::VescToOdom::last_servo_cmd_ |
|
private |
Last servo position commanded value.
Definition at line 61 of file vesc_to_odom.h.
vesc_msgs::VescStateStamped::ConstPtr vesc_ackermann::VescToOdom::last_state_ |
|
private |
std::string vesc_ackermann::VescToOdom::odom_frame_ |
|
private |
bool vesc_ackermann::VescToOdom::publish_tf_ |
|
private |
double vesc_ackermann::VescToOdom::speed_to_erpm_gain_ |
|
private |
double vesc_ackermann::VescToOdom::speed_to_erpm_offset_ |
|
private |
double vesc_ackermann::VescToOdom::steering_to_servo_gain_ |
|
private |
double vesc_ackermann::VescToOdom::steering_to_servo_offset_ |
|
private |
bool vesc_ackermann::VescToOdom::use_servo_cmd_ |
|
private |
State message does not report servo position, so use the command instead
Definition at line 52 of file vesc_to_odom.h.
double vesc_ackermann::VescToOdom::wheelbase_ |
|
private |
double vesc_ackermann::VescToOdom::x_ |
|
private |
double vesc_ackermann::VescToOdom::y_ |
|
private |
double vesc_ackermann::VescToOdom::yaw_ |
|
private |
The documentation for this class was generated from the following files: