目录
- 前言
- 正文
- 创建功能包
- 具体代码
- 运行
- 总结
前言
dual_arm_pick-place
项目中,实现了两套的moveit和gazebo联合仿真。
启动文件分别是bringup_moveit.launch
和arm_bringup_moveit.launch
。
在这个项目中,我将代码重新创建了一个包,co_simulation
,这个包里面只需要五个文件**(两个yaml文件,三个launch文件)**,我尝试后,就能够实现联合仿真,而且调用的是我自己创建的moveit配置助手包marm_moveit_config
。
这个意思是说,理论上来说,我们不需要对moveit配置助手包
内容进行任何改变操作,就能够实现联合仿真。
但是,不好意思的是,目前我只在这里进行了测试,其他项目中,还没来得及测试,但是,我觉得,肯定会遇到一些问题。
不过,本项目是可以完全放心使用的。
正文
这里需要注意的是,我上文中说的是五个文件,有同学会问,这里不是六个嘛。
bringup_moveit_config.launch
是使用的我自己创建的moveit配置助手创建的包marm_moveit_config,里面内容没有更改。bringup_moveit.launch
使用的是作者使用moveit配置助手创建的marmbots
包。
两种我都试过了,都可以实现联合仿真。所以我才说的,不需要修改moveit配置助手包
就能使用。
创建功能包
catkin_create_pkg co_simulation urdf xacro gazebo_ros gazebo_ros_control gazebo_plugins
我这里创建功能包,喜欢多写一些依赖项。
项目树长这样
├── CMakeLists.txt
├── config
│ ├── joint_state_controller.yaml
│ └── trajectory_controller.yaml
├── launch
│ ├── bringup_gazebo.launch
│ ├── bringup_moveit_config.launch
│ ├── bringup_moveit.launch
│ └── controller_utils.launch
└── package.xml
具体代码
co_simulation/config/joint_state_controller.yaml
joint_state_controller:type: joint_state_controller/JointStateControllerpublish_rate: 50
co_simulation/config/trajectory_controller.yaml
arma_trajectory_controller:type: "position_controllers/JointTrajectoryController"joints:- joint1a- joint2a- joint3a- joint4a- joint5a- joint6aconstraints:goal_time: 0.6stopped_velocity_tolerance: 0.05joint1a: {trajectory: 0.1, goal: 0.1}joint2a: {trajectory: 0.1, goal: 0.1}joint3a: {trajectory: 0.1, goal: 0.1}joint4a: {trajectory: 0.1, goal: 0.1}joint5a: {trajectory: 0.1, goal: 0.1}joint6a: {trajectory: 0.1, goal: 0.1}stop_trajectory_duration: 0.5state_publish_rate: 25action_monitor_rate: 10armb_trajectory_controller:type: "position_controllers/JointTrajectoryController"joints:- joint1b- joint2b- joint3b- joint4b- joint5b- joint6bconstraints:goal_time: 0.6stopped_velocity_tolerance: 0.05joint1b: {trajectory: 0.1, goal: 0.1}joint2b: {trajectory: 0.1, goal: 0.1}joint3b: {trajectory: 0.1, goal: 0.1}joint4b: {trajectory: 0.1, goal: 0.1}joint5b: {trajectory: 0.1, goal: 0.1}joint6b: {trajectory: 0.1, goal: 0.1}stop_trajectory_duration: 0.5state_publish_rate: 25action_monitor_rate: 10#notice that the grippers joint2 mimics joint1
#this is why it is not listed under the hand controllers
handa_controller:type: "position_controllers/JointTrajectoryController"joints:- finger_joint1agains:finger_joint1a: {p: 50.0, d: 1.0, i: 0.01, i_clamp: 1.0}handb_controller:type: "position_controllers/JointTrajectoryController"joints:- finger_joint1bgains:finger_joint1b: {p: 50.0, d: 1.0, i: 0.01, i_clamp: 1.0}
co_simulation/launch/bringup_gazebo.launch
<?xml version="1.0"?>
<launch>
<!-- 打开gazebo仿真 --><!-- Launch empty Gazebo world --><include file="$(find gazebo_ros)/launch/empty_world.launch"><arg name="use_sim_time" value="true" /><!-- <arg name="world_name" value="$(find test_gazebos_att)/worlds/test_attacher.world"/> --><arg name="gui" value="true" /><arg name="paused" value="false" /><arg name="debug" value="false" /></include><!-- Load the robot description file--><param name="robot_description" command="$(find xacro)/xacro '$(find marm_description)/urdf/arms2b.xacro'" /><!-- Spawn the robot over the robot_description param--><node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen" args="-urdf -param robot_description -model arms" />
</launch>
co_simulation/launch/bringup_moveit_config.launch
<?xml version="1.0"?>
<launch><!-- Run the main MoveIt executable with trajectory execution --><include file="$(find marm_moveit_config)/launch/move_group.launch"><arg name="allow_trajectory_execution" value="true" /><arg name="moveit_controller_manager" value="ros_control" /><arg name="fake_execution_type" value="interpolate" /><arg name="info" value="true" /><arg name="debug" value="false" /><arg name="pipeline" value="ompl" /><arg name="load_robot_description" value="true" /></include><!-- Start the simulated robot in an empty Gazebo world --><include file="$(find co_simulation)/launch/bringup_gazebo.launch" /><!-- Start the controllers and robot state publisher--><include file="$(find co_simulation)/launch/controller_utils.launch"/><!-- Start moveit_rviz with the motion planning plugin --><include file="$(find marm_moveit_config)/launch/moveit_rviz.launch"><arg name="rviz_config" value="$(find marm_moveit_config)/launch/moveit.rviz" /></include></launch>
co_simulation/launch/bringup_moveit.launch
<?xml version="1.0"?>
<launch><!-- Run the main MoveIt executable with trajectory execution --><include file="$(find marmbots)/launch/move_group.launch"><arg name="allow_trajectory_execution" value="true" /><arg name="moveit_controller_manager" value="ros_control" /><arg name="fake_execution_type" value="interpolate" /><arg name="info" value="true" /><arg name="debug" value="false" /><arg name="pipeline" value="ompl" /><arg name="load_robot_description" value="true" /></include><!-- Start the simulated robot in an empty Gazebo world --><include file="$(find co_simulation)/launch/bringup_gazebo.launch" /><!-- Start the controllers and robot state publisher--><include file="$(find co_simulation)/launch/controller_utils.launch"/><!-- Start moveit_rviz with the motion planning plugin --><include file="$(find marmbots)/launch/moveit_rviz.launch"><arg name="rviz_config" value="$(find marmbots)/launch/moveit.rviz" /></include></launch>
co_simulation/launch/controller_utils.launch
<?xml version="1.0"?>
<launch><!-- Robot state publisher --><node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher"><param name="publish_frequency" type="double" value="50.0" /><param name="tf_prefix" type="string" value="" /></node><!-- Joint state controller --><rosparam file="$(find co_simulation)/config/joint_state_controller.yaml" command="load" /><node name="joint_state_controller_spawner" pkg="controller_manager" type="spawner" args="joint_state_controller" respawn="false" output="screen" /><!-- Joint trajectory controller --><rosparam file="$(find co_simulation)/config/trajectory_controller.yaml" command="load" /><node name="arms_trajectory_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="arma_trajectory_controller armb_trajectory_controller handa_controller handb_controller" /></launch>
运行
以下两个命令都可以实现
roslaunch co_simulation bringup_moveit.launch
roslaunch co_simulation bringup_moveit_config.launch
总结
用这种方式实现联合仿真比较简单,但是,不太清楚,其他的项目,能否用这种方式去实现。