在上一篇文章中我们已经使用SolidWorks完成了机器人的建模与配置,使其能在gazebo与rviz中加载控制,接下来则需要对传动装置和控制器进行配置,以便后续编写控制算法进行仿真
配置传动装置相当于配置各个关节的舵机参数。代码如下(示例):
<?xml version="1.0" ?>
<robot name="my_robot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- Transmissions for ros_control -->
<xacro:macro name="transmission_block" params="joint_name">
<transmission name="trans1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${joint_name}">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor1">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
<xacro:transmission_block joint_name="joint_1"/>
<xacro:transmission_block joint_name="joint_2"/>
<xacro:transmission_block joint_name="joint_3"/>
<xacro:transmission_block joint_name="joint_4"/>
<xacro:transmission_block joint_name="joint_5"/>
<xacro:transmission_block joint_name="joint_6"/>
<xacro:transmission_block joint_name="joint_7"/>
<xacro:transmission_block joint_name="joint_8"/>
<xacro:transmission_block joint_name="joint_9"/>
<xacro:transmission_block joint_name="joint_10"/>
<xacro:transmission_block joint_name="joint_11"/>
<xacro:transmission_block joint_name="joint_12"/>
<xacro:transmission_block joint_name="joint_13"/>
<xacro:transmission_block joint_name="joint_14"/>
<xacro:transmission_block joint_name="joint_15"/>
<xacro:transmission_block joint_name="joint_16"/>
<xacro:transmission_block joint_name="joint_17"/>
<xacro:transmission_block joint_name="joint_18"/>
</robot>
代码如下(示例):
<?xml version="1.0"?>
<robot name="my_robot" xmlns:xacro="http://www.ros.org/wiki/xacro">
#添加ros_control插件
<!-- ros_control plugin -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/my_robot</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>
#配置关节阻尼
<!-- Joint 'implicitSpringDamper' setup-->
<xacro:macro name="joint_setup_block" params="joint_name">
<gazebo reference="${joint_name}">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
</xacro:macro>
<xacro:joint_setup_block joint_name="joint_1"/>
<xacro:joint_setup_block joint_name="joint_2"/>
<xacro:joint_setup_block joint_name="joint_3"/>
<xacro:joint_setup_block joint_name="joint_4"/>
<xacro:joint_setup_block joint_name="joint_5"/>
<xacro:joint_setup_block joint_name="joint_6"/>
<xacro:joint_setup_block joint_name="joint_7"/>
<xacro:joint_setup_block joint_name="joint_8"/>
<xacro:joint_setup_block joint_name="joint_9"/>
<xacro:joint_setup_block joint_name="joint_10"/>
<xacro:joint_setup_block joint_name="joint_11"/>
<xacro:joint_setup_block joint_name="joint_12"/>
<xacro:joint_setup_block joint_name="joint_13"/>
<xacro:joint_setup_block joint_name="joint_14"/>
<xacro:joint_setup_block joint_name="joint_15"/>
<xacro:joint_setup_block joint_name="joint_16"/>
<xacro:joint_setup_block joint_name="joint_17"/>
<xacro:joint_setup_block joint_name="joint_18"/>
#配置连杆物理属性,主要配置机器人末端与世界接触的物理属性。
<!-- Link setup-->
<xacro:macro name="link_setup_block" params="link_name">
<gazebo reference="${link_name}">
<kp>1000000.0</kp>
<kd>1.0</kd>
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<minDepth>0.001</minDepth>
</gazebo>
</xacro:macro>
<xacro:link_setup_block link_name="13"/>
<xacro:link_setup_block link_name="14"/>
<xacro:link_setup_block link_name="15"/>
<xacro:link_setup_block link_name="16"/>
<xacro:link_setup_block link_name="17"/>
<xacro:link_setup_block link_name="18"/>
</robot>
主要配置的有:控制器信息发布频率和各个关节的pid参数:
my_robot:
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 10
# Position Controllers ---------------------------------------
joint1_position_controller:
type: effort_controllers/JointPositionController
joint: joint_1
pid: {p: 5000.0, i: 0.01, d: 100.0}
joint2_position_controller:
type: effort_controllers/JointPositionController
joint: joint_2
pid: {p: 5000.0, i: 0.01, d: 100.0}
joint3_position_controller:
type: effort_controllers/JointPositionController
joint: joint_3
pid: {p: 5000.0, i: 0.01, d: 100.0}
joint4_position_controller:
type: effort_controllers/JointPositionController
joint: joint_4
pid: {p: 5000.0, i: 0.01, d: 100.0}
joint5_position_controller:
type: effort_controllers/JointPositionController
joint: joint_5
pid: {p: 5000.0, i: 0.01, d: 100.0}
joint6_position_controller:
type: effort_controllers/JointPositionController
joint: joint_6
pid: {p: 5000.0, i: 0.01, d: 100.0}
joint7_position_controller:
type: effort_controllers/JointPositionController
joint: joint_7
pid: {p: 5000.0, i: 0.01, d: 100.0}
joint8_position_controller:
type: effort_controllers/JointPositionController
joint: joint_8
pid: {p: 5000.0, i: 0.01, d: 100.0}
joint9_position_controller:
type: effort_controllers/JointPositionController
joint: joint_9
pid: {p: 5000.0, i: 0.01, d: 100.0}
joint10_position_controller:
type: effort_controllers/JointPositionController
joint: joint_10
pid: {p: 5000.0, i: 0.01, d: 100.0}
joint11_position_controller:
type: effort_controllers/JointPositionController
joint: joint_11
pid: {p: 5000.0, i: 0.01, d: 100.0}
joint12_position_controller:
type: effort_controllers/JointPositionController
joint: joint_12
pid: {p: 3000.0, i: 0.01, d: 100.0}
joint13_position_controller:
type: effort_controllers/JointPositionController
joint: joint_13
pid: {p: 5000.0, i: 0.01, d: 100.0}
joint14_position_controller:
type: effort_controllers/JointPositionController
joint: joint_14
pid: {p: 5000.0, i: 0.01, d: 100.0}
joint15_position_controller:
type: effort_controllers/JointPositionController
joint: joint_15
pid: {p: 5000.0, i: 0.01, d: 100.0}
joint16_position_controller:
type: effort_controllers/JointPositionController
joint: joint_16
pid: {p: 5000.0, i: 0.01, d: 100.0}
joint17_position_controller:
type: effort_controllers/JointPositionController
joint: joint_17
pid: {p: 5000.0, i: 0.01, d: 100.0}
joint18_position_controller:
type: effort_controllers/JointPositionController
joint: joint_18
pid: {p: 3000.0, i: 0.01, d: 100.0}
将新增的节点添加入launch文件即可:
<launch>
<param name="/use_sim_time" value="true" />
<arg name="world_name" value="$(find my_robot)/worlds/empty_world.world"/>
<arg name="paused" default="true"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(arg world_name)"/>
<arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gui)" />
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
include>
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<rosparam param="/source_list">[/my_robot/joint_states]rosparam>
node>
<param name="robot_description" command="$(find xacro)/xacro --inorder $(find my_robot)/urdf/bot.xacro"/>
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen" args="-urdf -model my_robot -param robot_description"/>
<rosparam file="$(find robot_control)/config/control.yaml" command="load"/>
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" ns="my_robot"
output="screen" args="joint_state_controller
joint1_position_controller
joint2_position_controller
joint3_position_controller
joint4_position_controller
joint5_position_controller
joint6_position_controller
joint7_position_controller
joint8_position_controller
joint9_position_controller
joint10_position_controller
joint11_position_controller
joint12_position_controller
joint13_position_controller
joint14_position_controller
joint15_position_controller
joint16_position_controller
joint17_position_controller
joint18_position_controller"/>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="false" output="screen">
<remap from="/joint_states" to="/my_robot/joint_states" />
node>
launch>
通过上述步骤便可完成机器人控制器的配置,接下来便可通过编写控制算法进行运动仿真。需要注意的是仿真对模型的参数有较高的要求(最好与真实机器人相同),否则仿真会出现各种问题,导致效果不理想。