#include <gazebo_ros_diff_drive.h>
Definition at line 73 of file gazebo_ros_diff_drive.h.
◆ OdomSource
◆ GazeboRosDiffDrive()
gazebo::GazeboRosDiffDrive::GazeboRosDiffDrive |
( |
| ) |
|
◆ ~GazeboRosDiffDrive()
gazebo::GazeboRosDiffDrive::~GazeboRosDiffDrive |
( |
| ) |
|
◆ cmdVelCallback()
void gazebo::GazeboRosDiffDrive::cmdVelCallback |
( |
const geometry_msgs::Twist::ConstPtr & |
cmd_msg | ) |
|
|
private |
◆ FiniChild()
void gazebo::GazeboRosDiffDrive::FiniChild |
( |
| ) |
|
|
protectedvirtual |
◆ getWheelVelocities()
void gazebo::GazeboRosDiffDrive::getWheelVelocities |
( |
| ) |
|
|
private |
◆ Load()
void gazebo::GazeboRosDiffDrive::Load |
( |
physics::ModelPtr |
_parent, |
|
|
sdf::ElementPtr |
_sdf |
|
) |
| |
◆ publishOdometry()
void gazebo::GazeboRosDiffDrive::publishOdometry |
( |
double |
step_time | ) |
|
|
private |
◆ publishWheelJointState()
void gazebo::GazeboRosDiffDrive::publishWheelJointState |
( |
| ) |
|
|
private |
◆ publishWheelTF()
void gazebo::GazeboRosDiffDrive::publishWheelTF |
( |
| ) |
|
|
private |
◆ QueueThread()
void gazebo::GazeboRosDiffDrive::QueueThread |
( |
| ) |
|
|
private |
◆ Reset()
void gazebo::GazeboRosDiffDrive::Reset |
( |
| ) |
|
◆ UpdateChild()
void gazebo::GazeboRosDiffDrive::UpdateChild |
( |
| ) |
|
|
protectedvirtual |
◆ UpdateOdometryEncoder()
void gazebo::GazeboRosDiffDrive::UpdateOdometryEncoder |
( |
| ) |
|
|
private |
◆ alive_
bool gazebo::GazeboRosDiffDrive::alive_ |
|
private |
◆ callback_queue_thread_
boost::thread gazebo::GazeboRosDiffDrive::callback_queue_thread_ |
|
private |
◆ cmd_vel_subscriber_
◆ command_topic_
std::string gazebo::GazeboRosDiffDrive::command_topic_ |
|
private |
◆ gazebo_ros_
◆ joint_state_
sensor_msgs::JointState gazebo::GazeboRosDiffDrive::joint_state_ |
|
private |
◆ joint_state_publisher_
◆ joints_
std::vector<physics::JointPtr> gazebo::GazeboRosDiffDrive::joints_ |
|
private |
◆ last_odom_update_
common::Time gazebo::GazeboRosDiffDrive::last_odom_update_ |
|
private |
◆ last_update_time_
common::Time gazebo::GazeboRosDiffDrive::last_update_time_ |
|
private |
◆ lock
boost::mutex gazebo::GazeboRosDiffDrive::lock |
|
private |
◆ odom_
nav_msgs::Odometry gazebo::GazeboRosDiffDrive::odom_ |
|
private |
◆ odom_source_
OdomSource gazebo::GazeboRosDiffDrive::odom_source_ |
|
private |
◆ odometry_frame_
std::string gazebo::GazeboRosDiffDrive::odometry_frame_ |
|
private |
◆ odometry_publisher_
◆ odometry_topic_
std::string gazebo::GazeboRosDiffDrive::odometry_topic_ |
|
private |
◆ parent
physics::ModelPtr gazebo::GazeboRosDiffDrive::parent |
|
private |
◆ pose_encoder_
geometry_msgs::Pose2D gazebo::GazeboRosDiffDrive::pose_encoder_ |
|
private |
◆ publish_tf_
bool gazebo::GazeboRosDiffDrive::publish_tf_ |
|
private |
◆ publishOdomTF_
bool gazebo::GazeboRosDiffDrive::publishOdomTF_ |
|
private |
◆ publishWheelJointState_
bool gazebo::GazeboRosDiffDrive::publishWheelJointState_ |
|
private |
◆ publishWheelTF_
bool gazebo::GazeboRosDiffDrive::publishWheelTF_ |
|
private |
◆ queue_
◆ robot_base_frame_
std::string gazebo::GazeboRosDiffDrive::robot_base_frame_ |
|
private |
◆ robot_namespace_
std::string gazebo::GazeboRosDiffDrive::robot_namespace_ |
|
private |
◆ rot_
double gazebo::GazeboRosDiffDrive::rot_ |
|
private |
◆ tf_prefix_
std::string gazebo::GazeboRosDiffDrive::tf_prefix_ |
|
private |
◆ transform_broadcaster_
◆ update_connection_
◆ update_period_
double gazebo::GazeboRosDiffDrive::update_period_ |
|
private |
◆ update_rate_
double gazebo::GazeboRosDiffDrive::update_rate_ |
|
private |
◆ wheel_accel
double gazebo::GazeboRosDiffDrive::wheel_accel |
|
private |
◆ wheel_diameter_
double gazebo::GazeboRosDiffDrive::wheel_diameter_ |
|
private |
◆ wheel_separation_
double gazebo::GazeboRosDiffDrive::wheel_separation_ |
|
private |
◆ wheel_speed_
double gazebo::GazeboRosDiffDrive::wheel_speed_[2] |
|
private |
◆ wheel_speed_instr_
double gazebo::GazeboRosDiffDrive::wheel_speed_instr_[2] |
|
private |
◆ wheel_torque
double gazebo::GazeboRosDiffDrive::wheel_torque |
|
private |
◆ x_
double gazebo::GazeboRosDiffDrive::x_ |
|
private |
The documentation for this class was generated from the following files: