Classes | Public Member Functions | Protected Member Functions | Private Types | Private Member Functions | Private Attributes
gazebo::GazeboRosTricycleDrive Class Reference

#include <gazebo_ros_tricycle_drive.h>

List of all members.

Classes

class  TricycleDriveCmd

Public Member Functions

 GazeboRosTricycleDrive ()
void Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf)
 ~GazeboRosTricycleDrive ()

Protected Member Functions

virtual void FiniChild ()
virtual void UpdateChild ()

Private Types

enum  OdomSource { ENCODER = 0, WORLD = 1 }

Private Member Functions

void cmdVelCallback (const geometry_msgs::Twist::ConstPtr &cmd_msg)
void motorController (double target_speed, double target_angle, double dt)
void publishOdometry (double step_time)
void publishWheelJointState ()
 publishes the wheel tf's
void publishWheelTF ()
void QueueThread ()
void UpdateOdometryEncoder ()
 updates the relative robot pose based on the wheel encoders

Private Attributes

bool alive_
boost::thread callback_queue_thread_
TricycleDriveCmd cmd_
ros::Subscriber cmd_vel_subscriber_
std::string command_topic_
double diameter_actuated_wheel_
double diameter_encoder_wheel_
GazeboRosPtr gazebo_ros_
sensor_msgs::JointState joint_state_
ros::Publisher joint_state_publisher_
physics::JointPtr joint_steering_
physics::JointPtr joint_wheel_actuated_
physics::JointPtr joint_wheel_encoder_left_
physics::JointPtr joint_wheel_encoder_right_
common::Time last_actuator_update_
common::Time last_odom_update_
boost::mutex lock
nav_msgs::Odometry odom_
OdomSource odom_source_
std::string odometry_frame_
ros::Publisher odometry_publisher_
std::string odometry_topic_
physics::ModelPtr parent
geometry_msgs::Pose2D pose_encoder_
bool publishWheelJointState_
bool publishWheelTF_
ros::CallbackQueue queue_
std::string robot_base_frame_
std::string robot_namespace_
double separation_encoder_wheel_
double steering_angle_tolerance_
double steering_speed_
boost::shared_ptr
< tf::TransformBroadcaster
transform_broadcaster_
event::ConnectionPtr update_connection_
double update_period_
double update_rate_
double wheel_acceleration_
double wheel_deceleration_
double wheel_speed_tolerance_
double wheel_torque_

Detailed Description

Definition at line 73 of file gazebo_ros_tricycle_drive.h.


Member Enumeration Documentation

Enumerator:
ENCODER 
WORLD 

Definition at line 82 of file gazebo_ros_tricycle_drive.h.


Constructor & Destructor Documentation

Definition at line 67 of file gazebo_ros_tricycle_drive.cpp.

Definition at line 70 of file gazebo_ros_tricycle_drive.cpp.


Member Function Documentation

void gazebo::GazeboRosTricycleDrive::cmdVelCallback ( const geometry_msgs::Twist::ConstPtr &  cmd_msg) [private]

Definition at line 288 of file gazebo_ros_tricycle_drive.cpp.

void gazebo::GazeboRosTricycleDrive::FiniChild ( ) [protected, virtual]

Definition at line 279 of file gazebo_ros_tricycle_drive.cpp.

void gazebo::GazeboRosTricycleDrive::Load ( physics::ModelPtr  _parent,
sdf::ElementPtr  _sdf 
)

Definition at line 73 of file gazebo_ros_tricycle_drive.cpp.

void gazebo::GazeboRosTricycleDrive::motorController ( double  target_speed,
double  target_angle,
double  dt 
) [private]

Definition at line 226 of file gazebo_ros_tricycle_drive.cpp.

void gazebo::GazeboRosTricycleDrive::publishOdometry ( double  step_time) [private]

Definition at line 350 of file gazebo_ros_tricycle_drive.cpp.

publishes the wheel tf's

Definition at line 157 of file gazebo_ros_tricycle_drive.cpp.

Definition at line 180 of file gazebo_ros_tricycle_drive.cpp.

Definition at line 295 of file gazebo_ros_tricycle_drive.cpp.

void gazebo::GazeboRosTricycleDrive::UpdateChild ( ) [protected, virtual]

Definition at line 203 of file gazebo_ros_tricycle_drive.cpp.

updates the relative robot pose based on the wheel encoders

Definition at line 304 of file gazebo_ros_tricycle_drive.cpp.


Member Data Documentation

Definition at line 152 of file gazebo_ros_tricycle_drive.h.

Definition at line 142 of file gazebo_ros_tricycle_drive.h.

Definition at line 151 of file gazebo_ros_tricycle_drive.h.

Definition at line 131 of file gazebo_ros_tricycle_drive.h.

Definition at line 124 of file gazebo_ros_tricycle_drive.h.

Definition at line 112 of file gazebo_ros_tricycle_drive.h.

Definition at line 111 of file gazebo_ros_tricycle_drive.h.

Definition at line 97 of file gazebo_ros_tricycle_drive.h.

sensor_msgs::JointState gazebo::GazeboRosTricycleDrive::joint_state_ [private]

Definition at line 133 of file gazebo_ros_tricycle_drive.h.

Definition at line 134 of file gazebo_ros_tricycle_drive.h.

Definition at line 106 of file gazebo_ros_tricycle_drive.h.

Definition at line 107 of file gazebo_ros_tricycle_drive.h.

Definition at line 108 of file gazebo_ros_tricycle_drive.h.

Definition at line 109 of file gazebo_ros_tricycle_drive.h.

Definition at line 159 of file gazebo_ros_tricycle_drive.h.

Definition at line 154 of file gazebo_ros_tricycle_drive.h.

boost::mutex gazebo::GazeboRosTricycleDrive::lock [private]

Definition at line 137 of file gazebo_ros_tricycle_drive.h.

nav_msgs::Odometry gazebo::GazeboRosTricycleDrive::odom_ [private]

Definition at line 135 of file gazebo_ros_tricycle_drive.h.

Definition at line 120 of file gazebo_ros_tricycle_drive.h.

Definition at line 126 of file gazebo_ros_tricycle_drive.h.

Definition at line 130 of file gazebo_ros_tricycle_drive.h.

Definition at line 125 of file gazebo_ros_tricycle_drive.h.

physics::ModelPtr gazebo::GazeboRosTricycleDrive::parent [private]

Definition at line 98 of file gazebo_ros_tricycle_drive.h.

geometry_msgs::Pose2D gazebo::GazeboRosTricycleDrive::pose_encoder_ [private]

Definition at line 153 of file gazebo_ros_tricycle_drive.h.

Definition at line 163 of file gazebo_ros_tricycle_drive.h.

Definition at line 162 of file gazebo_ros_tricycle_drive.h.

Definition at line 141 of file gazebo_ros_tricycle_drive.h.

Definition at line 127 of file gazebo_ros_tricycle_drive.h.

Definition at line 123 of file gazebo_ros_tricycle_drive.h.

Definition at line 118 of file gazebo_ros_tricycle_drive.h.

Definition at line 116 of file gazebo_ros_tricycle_drive.h.

Definition at line 117 of file gazebo_ros_tricycle_drive.h.

Definition at line 132 of file gazebo_ros_tricycle_drive.h.

Definition at line 104 of file gazebo_ros_tricycle_drive.h.

Definition at line 158 of file gazebo_ros_tricycle_drive.h.

Definition at line 157 of file gazebo_ros_tricycle_drive.h.

Definition at line 113 of file gazebo_ros_tricycle_drive.h.

Definition at line 114 of file gazebo_ros_tricycle_drive.h.

Definition at line 115 of file gazebo_ros_tricycle_drive.h.

Definition at line 121 of file gazebo_ros_tricycle_drive.h.


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


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Jun 6 2019 18:41:10