Class GazeboRosTricycleDrive
Defined in File gazebo_ros_tricycle_drive.hpp
Class Documentation
-
class gazebo_plugins::GazeboRosTricycleDrive : public ModelPlugin
A tricycle drive plugin for gazebo.
Example Usage:
<plugin name='tricycle_drive' filename='libgazebo_ros_tricycle_drive.so'> <ros> <namespace></namespace> <remapping>cmd_vel:=cmd_vel</remapping> <remapping>odom:=odom</remapping> </ros> <!-- wheels --> <steering_joint>wheel_front_steer</steering_joint> <actuated_wheel_joint>wheel_front_spin</actuated_wheel_joint> <encoder_wheel_left_joint>wheel_rear_left_spin</encoder_wheel_left_joint> <encoder_wheel_right_joint>wheel_rear_right_spin</encoder_wheel_right_joint> <!-- kinematics --> <wheel_separation>1.0</wheel_separation> <encoder_wheel_diameter>0.3</encoder_wheel_diameter> <actuated_wheel_diameter>0.3</actuated_wheel_diameter> <!-- limits --> <max_wheel_torque>20</max_wheel_torque> <max_wheel_acceleration>5.0</max_wheel_acceleration> <max_steering_speed>1.0</max_steering_speed> <!-- output --> <publish_odom>true</publish_odom> <publish_wheel_tf>true</publish_wheel_tf> <publish_wheel_joint_state>true</publish_wheel_joint_state> <odometry_frame>odom</odometry_frame> <robot_base_frame>fork</robot_base_frame> </plugin>