#include <gazebo_ros_tricycle_drive.h>
Definition at line 73 of file gazebo_ros_tricycle_drive.h.
gazebo::GazeboRosTricycleDrive::GazeboRosTricycleDrive |
( |
| ) |
|
gazebo::GazeboRosTricycleDrive::~GazeboRosTricycleDrive |
( |
| ) |
|
void gazebo::GazeboRosTricycleDrive::cmdVelCallback |
( |
const geometry_msgs::Twist::ConstPtr & |
cmd_msg | ) |
|
|
private |
void gazebo::GazeboRosTricycleDrive::FiniChild |
( |
| ) |
|
|
protectedvirtual |
void gazebo::GazeboRosTricycleDrive::Load |
( |
physics::ModelPtr |
_parent, |
|
|
sdf::ElementPtr |
_sdf |
|
) |
| |
void gazebo::GazeboRosTricycleDrive::motorController |
( |
double |
target_speed, |
|
|
double |
target_angle, |
|
|
double |
dt |
|
) |
| |
|
private |
void gazebo::GazeboRosTricycleDrive::publishOdometry |
( |
double |
step_time | ) |
|
|
private |
void gazebo::GazeboRosTricycleDrive::publishWheelJointState |
( |
| ) |
|
|
private |
void gazebo::GazeboRosTricycleDrive::publishWheelTF |
( |
| ) |
|
|
private |
void gazebo::GazeboRosTricycleDrive::QueueThread |
( |
| ) |
|
|
private |
void gazebo::GazeboRosTricycleDrive::UpdateChild |
( |
| ) |
|
|
protectedvirtual |
void gazebo::GazeboRosTricycleDrive::UpdateOdometryEncoder |
( |
| ) |
|
|
private |
bool gazebo::GazeboRosTricycleDrive::alive_ |
|
private |
boost::thread gazebo::GazeboRosTricycleDrive::callback_queue_thread_ |
|
private |
std::string gazebo::GazeboRosTricycleDrive::command_topic_ |
|
private |
double gazebo::GazeboRosTricycleDrive::diameter_actuated_wheel_ |
|
private |
double gazebo::GazeboRosTricycleDrive::diameter_encoder_wheel_ |
|
private |
sensor_msgs::JointState gazebo::GazeboRosTricycleDrive::joint_state_ |
|
private |
physics::JointPtr gazebo::GazeboRosTricycleDrive::joint_steering_ |
|
private |
physics::JointPtr gazebo::GazeboRosTricycleDrive::joint_wheel_actuated_ |
|
private |
physics::JointPtr gazebo::GazeboRosTricycleDrive::joint_wheel_encoder_left_ |
|
private |
physics::JointPtr gazebo::GazeboRosTricycleDrive::joint_wheel_encoder_right_ |
|
private |
common::Time gazebo::GazeboRosTricycleDrive::last_actuator_update_ |
|
private |
common::Time gazebo::GazeboRosTricycleDrive::last_odom_update_ |
|
private |
boost::mutex gazebo::GazeboRosTricycleDrive::lock |
|
private |
nav_msgs::Odometry gazebo::GazeboRosTricycleDrive::odom_ |
|
private |
OdomSource gazebo::GazeboRosTricycleDrive::odom_source_ |
|
private |
std::string gazebo::GazeboRosTricycleDrive::odometry_frame_ |
|
private |
std::string gazebo::GazeboRosTricycleDrive::odometry_topic_ |
|
private |
physics::ModelPtr gazebo::GazeboRosTricycleDrive::parent |
|
private |
geometry_msgs::Pose2D gazebo::GazeboRosTricycleDrive::pose_encoder_ |
|
private |
bool gazebo::GazeboRosTricycleDrive::publishWheelJointState_ |
|
private |
bool gazebo::GazeboRosTricycleDrive::publishWheelTF_ |
|
private |
std::string gazebo::GazeboRosTricycleDrive::robot_base_frame_ |
|
private |
std::string gazebo::GazeboRosTricycleDrive::robot_namespace_ |
|
private |
double gazebo::GazeboRosTricycleDrive::separation_encoder_wheel_ |
|
private |
double gazebo::GazeboRosTricycleDrive::steering_angle_tolerance_ |
|
private |
double gazebo::GazeboRosTricycleDrive::steering_speed_ |
|
private |
double gazebo::GazeboRosTricycleDrive::update_period_ |
|
private |
double gazebo::GazeboRosTricycleDrive::update_rate_ |
|
private |
double gazebo::GazeboRosTricycleDrive::wheel_acceleration_ |
|
private |
double gazebo::GazeboRosTricycleDrive::wheel_deceleration_ |
|
private |
double gazebo::GazeboRosTricycleDrive::wheel_speed_tolerance_ |
|
private |
double gazebo::GazeboRosTricycleDrive::wheel_torque_ |
|
private |
The documentation for this class was generated from the following files: