|
| | ROSComm (const ros::NodeHandle &n, double sigma_x, double sigma_theta, double cov_x_y, double cov_x_theta, double cov_y_theta, size_t num_wheels, std::vector< std::string > joint_names) |
| |
| 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::ROSComm |
( |
const ros::NodeHandle & |
n, |
|
|
double |
sigma_x, |
|
|
double |
sigma_theta, |
|
|
double |
cov_x_y, |
|
|
double |
cov_x_theta, |
|
|
double |
cov_y_theta, |
|
|
size_t |
num_wheels, |
|
|
std::vector< std::string > |
joint_names |
|
) |
| |
|
inline |
◆ populateCovariance()
| void ROSComm::populateCovariance |
( |
nav_msgs::Odometry & |
msg, |
|
|
double |
v_x, |
|
|
double |
v_theta |
|
) |
| |
|
private |
◆ send_odometry()
| void ROSComm::send_odometry |
( |
double |
x, |
|
|
double |
y, |
|
|
double |
theta, |
|
|
double |
v_x, |
|
|
double |
v_theta, |
|
|
double |
wheelpos_l, |
|
|
double |
wheelpos_r |
|
) |
| |
|
virtual |
◆ setTFPrefix()
| void ROSComm::setTFPrefix |
( |
const std::string & |
tf_prefix | ) |
|
◆ cov_x_theta_
| double ROSComm::cov_x_theta_ |
|
private |
◆ cov_x_y_
◆ cov_y_theta_
| double ROSComm::cov_y_theta_ |
|
private |
◆ joint_names_
| std::vector<std::string> ROSComm::joint_names_ |
|
private |
◆ joint_pub_
◆ n_
◆ num_wheels_
| size_t ROSComm::num_wheels_ |
|
private |
◆ odom_broadcaster_
◆ odom_pub_
◆ publish_tf_
| bool ROSComm::publish_tf_ |
|
private |
◆ sigma_theta_
| double ROSComm::sigma_theta_ |
|
private |
◆ sigma_x_
◆ tf_prefix_
| std::string ROSComm::tf_prefix_ |
|
private |
The documentation for this class was generated from the following file: