Public Member Functions | Private Member Functions | Private Attributes | List of all members
ROSComm Class Reference
Inheritance diagram for ROSComm:
Inheritance graph
[legend]

Public Member Functions

 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)
 
- Public Member Functions inherited from Comm
virtual ~Comm ()
 

Private Member Functions

void populateCovariance (nav_msgs::Odometry &msg, double v_x, double v_theta)
 

Private Attributes

double cov_x_theta_
 
double cov_x_y_
 
double cov_y_theta_
 
std::vector< std::string > joint_names_
 
ros::Publisher joint_pub_
 
ros::NodeHandle n_
 
size_t num_wheels_
 
tf::TransformBroadcaster odom_broadcaster_
 
ros::Publisher odom_pub_
 
bool publish_tf_
 
double sigma_theta_
 
double sigma_x_
 
std::string tf_prefix_
 

Detailed Description

Definition at line 42 of file volksbot_node.cpp.

Constructor & Destructor Documentation

◆ 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

Definition at line 45 of file volksbot_node.cpp.

Member Function Documentation

◆ populateCovariance()

void ROSComm::populateCovariance ( nav_msgs::Odometry &  msg,
double  v_x,
double  v_theta 
)
private

Definition at line 92 of file volksbot_node.cpp.

◆ 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

Implements Comm.

Definition at line 144 of file volksbot_node.cpp.

◆ setTFPrefix()

void ROSComm::setTFPrefix ( const std::string &  tf_prefix)

Definition at line 87 of file volksbot_node.cpp.

Member Data Documentation

◆ cov_x_theta_

double ROSComm::cov_x_theta_
private

Definition at line 76 of file volksbot_node.cpp.

◆ cov_x_y_

double ROSComm::cov_x_y_
private

Definition at line 76 of file volksbot_node.cpp.

◆ cov_y_theta_

double ROSComm::cov_y_theta_
private

Definition at line 76 of file volksbot_node.cpp.

◆ joint_names_

std::vector<std::string> ROSComm::joint_names_
private

Definition at line 84 of file volksbot_node.cpp.

◆ joint_pub_

ros::Publisher ROSComm::joint_pub_
private

Definition at line 82 of file volksbot_node.cpp.

◆ n_

ros::NodeHandle ROSComm::n_
private

Definition at line 75 of file volksbot_node.cpp.

◆ num_wheels_

size_t ROSComm::num_wheels_
private

Definition at line 83 of file volksbot_node.cpp.

◆ odom_broadcaster_

tf::TransformBroadcaster ROSComm::odom_broadcaster_
private

Definition at line 80 of file volksbot_node.cpp.

◆ odom_pub_

ros::Publisher ROSComm::odom_pub_
private

Definition at line 81 of file volksbot_node.cpp.

◆ publish_tf_

bool ROSComm::publish_tf_
private

Definition at line 77 of file volksbot_node.cpp.

◆ sigma_theta_

double ROSComm::sigma_theta_
private

Definition at line 76 of file volksbot_node.cpp.

◆ sigma_x_

double ROSComm::sigma_x_
private

Definition at line 76 of file volksbot_node.cpp.

◆ tf_prefix_

std::string ROSComm::tf_prefix_
private

Definition at line 78 of file volksbot_node.cpp.


The documentation for this class was generated from the following file:


volksbot_driver
Author(s): Jochen Sprickerhof
autogenerated on Tue Mar 1 2022 00:02:18