第三章、让小车动起来
1►配置controller
在tianracer_description功能包新建config文件夹时,我们可以通过一个yaml文件smart_control_config.yaml来声明我们所需要的controller,以及对应的参数,PID增益和 控制器设置必须保存在yaml文件中,再通过 launch文件加载到param服务器上:
tianracer:
# controls the rear two tires based on individual motors
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
rear_right_velocity_controller:
type: velocity_controllers/JointVelocityController
joint: right_rear_wheel_joint
pid: {p: 100.0, i: 0.01, d: 10.0}
rear_left_velocity_controller:
type: velocity_controllers/JointVelocityController
joint: left_rear_wheel_joint
pid: {p: 100.0, i: 0.01, d: 10.0}
front_right_steering_position_controller:
type: effort_controllers/JointPositionController
joint: right_steering_hinge_joint
pid: {p: 4.0, i: 2.0, d: 1.0}
front_left_steering_position_controller:
type: effort_controllers/JointPositionController
joint: left_steering_hinge_joint
pid: {p: 4.0, i: 2.0, d: 1.0}
gazebo_ros_control:
pid_gains:
right_rear_wheel_joint:
p: 100.0
i: 0.5
d: 0.0
left_rear_wheel_joint:
p: 100.0
i: 0.5
d: 0.0
2►配置launch文件
创建control.launch文件启动 ros_control controllers
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<!-- Load joint controller configurations from YAML file to parameter server -->
<rosparam file="$(find tianracer_description)/config/smart_control_config.yaml" command="load"/>
<!-- load controllers -->
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" ns="/tianracer" args="joint_state_controller rear_right_velocity_controller rear_left_velocity_controller front_right_steering_position_controller front_left_steering_position_controller"/>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
respawn="true" output="screen">
<remap from="/joint_states" to="/tianracer/joint_states" />
</node>
<node name="cmdvel2gazebo" pkg="tianracer_description" type="cmdvel2gazebo.py" respawn="true" output="screen"/>
</launch>
接着创建一个可以将小车模型在gazebo中打开的launch文件tianracer.launch,并且能够加载上述control.launch文件
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<!-- 设置launch文件的参数 -->
<arg name="paused" default="false"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>
<!--模型车的起点放置位置-->
<arg name="x_pos" default="0"/>
<arg name="y_pos" default="0"/>
<arg name="z_pos" default="0"/>
<arg name="R_pos" default="0"/>
<arg name="P_pos" default