|
| ROSComm (const ros::NodeHandle &n, double sigma_x, double sigma_theta, double cov_x_y, double cov_x_theta, double cov_y_theta) |
|
virtual void | send_odometry (double x, double y, double theta, double v_x, double v_theta, double wheelpos_l, double wheelpos_r) |
|
void | setTFPrefix (const std::string &tf_prefix) |
|
virtual | ~Comm () |
|
Definition at line 42 of file volksbot_node.cpp.
ROSComm::ROSComm |
( |
const ros::NodeHandle & |
n, |
|
|
double |
sigma_x, |
|
|
double |
sigma_theta, |
|
|
double |
cov_x_y, |
|
|
double |
cov_x_theta, |
|
|
double |
cov_y_theta |
|
) |
| |
|
inline |
void ROSComm::populateCovariance |
( |
nav_msgs::Odometry & |
msg, |
|
|
double |
v_x, |
|
|
double |
v_theta |
|
) |
| |
|
private |
void ROSComm::send_odometry |
( |
double |
x, |
|
|
double |
y, |
|
|
double |
theta, |
|
|
double |
v_x, |
|
|
double |
v_theta, |
|
|
double |
wheelpos_l, |
|
|
double |
wheelpos_r |
|
) |
| |
|
virtual |
void ROSComm::setTFPrefix |
( |
const std::string & |
tf_prefix | ) |
|
double ROSComm::cov_x_theta_ |
|
private |
double ROSComm::cov_y_theta_ |
|
private |
bool ROSComm::publish_tf_ |
|
private |
double ROSComm::sigma_theta_ |
|
private |
std::string ROSComm::tf_prefix_ |
|
private |
The documentation for this class was generated from the following file: